From 5964d95fd29473b13492847fc258f91e8b5940ba Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:10:48 +0100 Subject: [PATCH 01/33] Add files via upload --- .../DynamicWindowApproach/test_drone_DWA.py | 185 ++++++++++++++++++ 1 file changed, 185 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/test_drone_DWA.py diff --git a/PathPlanning/DynamicWindowApproach/test_drone_DWA.py b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py new file mode 100644 index 0000000000..1818a80f8c --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py @@ -0,0 +1,185 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +import time +import math +import threading +import matplotlib.pyplot as plt +import matplotlib.animation as animation +import numpy as np +import argparse +import random +import queue +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from dwa import Config, dwa_control, motion, RobotType, plot_robot + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True, timeout=60) +print('Connected to vehicle 1') + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True, timeout=60) +print('Connected to vehicle 2') + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def plot_destinations_and_fences(ax, start_position, destinations, fences): + ax.plot(start_position.lon, start_position.lat, 'bo', markersize=10, label="Start Position") + for dest in destinations: + ax.plot(dest[1], dest[0], 'go', markersize=8, label='Destination') + ax.text(dest[1] + 0.001, dest[0] + 0.001, 'Destination', fontsize=8, color='green') + for fence in fences: + ax.plot(fence['lon'], fence['lat'], 'ro', markersize=8, label='Fence') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +def drone_movement(vehicle, config, vehicle_id, destinations, plot_queue): + while True: + destination = random.choice(destinations) + goal = np.array([destination[0], destination[1]]) + ob = config.ob + + x = np.array([vehicle.location.global_relative_frame.lat, + vehicle.location.global_relative_frame.lon, + vehicle.attitude.yaw, 0.0, 0.0]) # Initial state + + while True: + print(f"Drone {vehicle_id} current position: {x[0]:.6f}, {x[1]:.6f}, yaw: {x[2]:.6f}") + # Call DWA control to get the control inputs and the trajectory + u, trajectory = dwa_control(x, config, goal, ob) + # Update the drone's state using the motion model + x = motion(x, u, config.dt) + + next_location = LocationGlobalRelative(x[0], x[1], vehicle.location.global_relative_frame.alt) + print(f"Drone {vehicle_id} moving to: {next_location.lat:.6f}, {next_location.lon:.6f}") + vehicle.simple_goto(next_location) + + # Add data to plot_queue + plot_queue.put((x[0], x[1], x[2], goal, ob, vehicle_id)) + + # Check if the drone has reached its goal + dist_to_goal = math.hypot(x[0] - goal[0], x[1] - goal[1]) + if dist_to_goal <= config.robot_radius: + print(f"Drone {vehicle_id} reached destination at {destination}") + break + + # Check if the drone is too close to any obstacle (fence) + for obstacle in ob: + dist_to_obstacle = math.hypot(x[0] - obstacle[0], x[1] - obstacle[1]) + if dist_to_obstacle <= config.robot_radius + 0.5: # Safety threshold + print(f"Drone {vehicle_id} too close to an obstacle, recalculating path...") + break + + print(f"Drone {vehicle_id} selecting new destination...") + +def plot_update(frame, plot_queue, ax, start_position, destinations, fences, config1, config2): + while not plot_queue.empty(): + x, y, yaw, goal, ob, vehicle_id = plot_queue.get() + ax.cla() + plot_destinations_and_fences(ax, start_position, destinations, fences) + plot_robot(x, y, yaw, config1 if vehicle_id == 1 else config2) + ax.plot(goal[0], goal[1], "xr", label='Goal') + ax.plot(ob[:, 1], ob[:, 0], "ok", label='Obstacle') + ax.set_aspect('equal') + ax.grid(True) + ax.set_xlim(0.46, 0.49) # Set x-axis limits to match the area + ax.set_ylim(51.68, 51.75) # Set y-axis limits to match the area + ax.legend() + +def arm_and_takeoff(vehicle, target_altitude): + while not vehicle.is_armable: + print("Waiting for vehicle to initialize...") + time.sleep(1) + + print("Arming motors") + vehicle.mode = VehicleMode("GUIDED") + vehicle.armed = True + + while not vehicle.armed: + print("Waiting for arming...") + time.sleep(1) + + print("Taking off!") + vehicle.simple_takeoff(target_altitude) + + while True: + print(f"Altitude: {vehicle.location.global_relative_frame.alt}") + if vehicle.location.global_relative_frame.alt >= target_altitude * 0.95: + print("Reached target altitude") + break + time.sleep(1) + +def main(): + arm_and_takeoff(vehicle1, 5) + time.sleep(10) # Wait for some time to ensure vehicle1 has taken off + arm_and_takeoff(vehicle2, 5) + time.sleep(10) # Wait for some time to ensure vehicle2 has taken off + + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for visualization + + destinations = [ + [51.75376, 0.48471, 45], # Springfield Hospital + [51.73112, 0.4711, 56], # Chelmsford & Essex Hospital + [51.73602, 0.47358, 33], # Fitzroy Surgery Chelmsford + [51.743516, 0.47556, 45], # Priory Hospital Chelmsford + [51.77517, 0.46596, 56] # Broomfield Hospital + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.74531, 'lon': 0.47058, 'radius': 0.0031477}, + {'name': 'Fence 2', 'lat': 51.73484, 'lon': 0.45986, 'radius': 0.0041471}, + {'name': 'Fence 3', 'lat': 51.715071, 'lon': 0.4858, 'radius': 0.0041471}, + {'name': 'Fence 4', 'lat': 51.75032, 'lon': 0.48405, 'radius': 0.00448}, + {'name': 'Fence 5', 'lat': 51.74856, 'lon': 0.48624, 'radius': 0.00448}, + {'name': 'Fence 6', 'lat': 51.73793, 'lon': 0.48606, 'radius': 0.0041471}, + {'name': 'Fence 7', 'lat': 51.76216, 'lon': 0.47748, 'radius': 0.00448}, + {'name': 'Fence 8', 'lat': 51.76928, 'lon': 0.46855, 'radius': 0.0041471} + ] + # Convert fences to obstacles for the DWA config + obstacles = [] + for fence in fences: + obstacles.append([fence['lat'], fence['lon']]) + + config1 = Config() + config1.robot_type = RobotType.circle + config1.ob = np.array(obstacles) + + config2 = Config() + config2.robot_type = RobotType.circle + config2.ob = np.array(obstacles) + + plot_queue = queue.Queue() + + vehicle1_thread = threading.Thread(target=drone_movement, args=(vehicle1, config1, 1, destinations, plot_queue)) + vehicle1_thread.daemon = True + vehicle1_thread.start() + + vehicle2_thread = threading.Thread(target=drone_movement, args=(vehicle2, config2, 2, destinations, plot_queue)) + vehicle2_thread.daemon = True + vehicle2_thread.start() + + fig, ax = plt.subplots(figsize=(10, 10)) # Increase the figure size + ani = animation.FuncAnimation(fig, plot_update, fargs=(plot_queue, ax, start_position, destinations, fences, config1, config2), interval=100, cache_frame_data=False) + + plt.show() + +if __name__ == '__main__': + main() + From 368740e7c34966a8a3cac00450b8a3018d0af5be Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:12:10 +0100 Subject: [PATCH 02/33] Add files via upload --- PathPlanning/AStar/test0.py | 302 ++++++++++++++++++++++++++++++++++ PathPlanning/AStar/test2.py | 314 ++++++++++++++++++++++++++++++++++++ 2 files changed, 616 insertions(+) create mode 100644 PathPlanning/AStar/test0.py create mode 100644 PathPlanning/AStar/test2.py diff --git a/PathPlanning/AStar/test0.py b/PathPlanning/AStar/test0.py new file mode 100644 index 0000000000..b51fa4bfe7 --- /dev/null +++ b/PathPlanning/AStar/test0.py @@ -0,0 +1,302 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function +import math +import matplotlib.pyplot as plt +import matplotlib.animation as animation +import numpy as np +import argparse +import threading +import sys +import pathlib +import time +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil + +sys.path.append(str(pathlib.Path(__file__).parent)) + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +class AStarPlanner: + def __init__(self, ox, oy, resolution, rr): + self.resolution = resolution + self.rr = rr + self.min_x, self.min_y = 0, 0 + self.max_x, self.max_y = 0, 0 + self.obstacle_map = None + self.x_width, self.y_width = 0, 0 + self.motion = self.get_motion_model() + self.calc_obstacle_map(ox, oy) + + class Node: + def __init__(self, x, y, cost, parent_index): + self.x = x + self.y = y + self.cost = cost + self.parent_index = parent_index + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.parent_index) + + def planning(self, sx, sy, gx, gy): + start_node = self.Node(self.calc_xy_index(sx, self.min_x), self.calc_xy_index(sy, self.min_y), 0.0, -1) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), self.calc_xy_index(gy, self.min_y), 0.0, -1) + + open_set, closed_set = dict(), dict() + open_set[self.calc_grid_index(start_node)] = start_node + + while True: + if len(open_set) == 0: + print("Open set is empty..") + break + + c_id = min(open_set, key=lambda o: open_set[o].cost + self.calc_heuristic(goal_node, open_set[o])) + current = open_set[c_id] + + if current.x == goal_node.x and current.y == goal_node.y: + print("Find goal") + goal_node.parent_index = current.parent_index + goal_node.cost = current.cost + break + + del open_set[c_id] + closed_set[c_id] = current + + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], current.cost + self.motion[i][2], c_id) + n_id = self.calc_grid_index(node) + + if not self.verify_node(node): + continue + + if n_id in closed_set: + continue + + if n_id not in open_set: + open_set[n_id] = node + else: + if open_set[n_id].cost > node.cost: + open_set[n_id] = node + + # Animation + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current.x, self.min_x), + self.calc_grid_position(current.y, self.min_y), "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: + plt.pause(0.001) + + rx, ry = self.calc_final_path(goal_node, closed_set) + + # Final path plot + if show_animation: + plt.plot(rx, ry, "-r") + plt.pause(0.001) + return rx, ry + + def calc_final_path(self, goal_node, closed_set): + rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [self.calc_grid_position(goal_node.y, self.min_y)] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] + rx.append(self.calc_grid_position(n.x, self.min_x)) + ry.append(self.calc_grid_position(n.y, self.min_y)) + parent_index = n.parent_index + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, min_position): + pos = index * self.resolution + min_position + return pos + + def calc_xy_index(self, position, min_pos): + return round((position - min_pos) / self.resolution) + + def calc_grid_index(self, node): + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.min_x) + py = self.calc_grid_position(node.y, self.min_y) + + if px < self.min_x or py < self.min_y or px >= self.max_x or py >= self.max_y: + return False + + if self.obstacle_map[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + + self.obstacle_map = [[False for _ in range(self.y_width)] for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_grid_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_grid_position(iy, self.min_y) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obstacle_map[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + return motion + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def plot_destinations_and_fences(ax, start_position, destinations, fences): + ax.plot(start_position.lon, start_position.lat, 'bo', label="Start Position") + for dest in destinations: + loc = dest['location'] + ax.plot(loc.lon, loc.lat, 'go') + ax.text(loc.lon + 0.001, loc.lat + 0.001, dest['name'], fontsize=8, color='green') + for fence in fences: + ax.plot(fence['lon'], fence['lat'], 'ro') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.725, 0.4700, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.715, 'lon': 0.471500, 'radius': 0.0061477}, + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4655, 'radius': 0.004471}, + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448}, + {'name': 'Fence 4', 'lat': 51.72171, 'lon': 0.482, 'radius': 0.004471} + ] + + fig, ax = plt.subplots(figsize=(18, 18)) # Increase the figure size + plt.ion() # Turn on interactive mode + + plot_destinations_and_fences(ax, start_position, destinations, fences) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(0.46, 0.49) # Set x-axis limits + ax.set_ylim(51.68, 51.75) # Set y-axis limits + + ox = [f['lat'] for f in fences] + oy = [f['lon'] for f in fences] + + # ====Search Path with A*==== + # Parameter + grid_size = 0.0001 # 10 meters + robot_radius = 0.0005 # 5 meters + + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + a_star = AStarPlanner(ox, oy, grid_size, robot_radius) + rx, ry = a_star.planning(start[0], start[1], goal[0], goal[1]) + + if not rx or not ry: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + all_paths.append(list(zip(rx, ry))) + + # Animate the paths + for path in all_paths: + x_data = [x for x, y in path] + y_data = [y for x, y in path] + ax.plot(x_data, y_data, "-r") + plt.pause(0.004) + plt.show() # Keep the plot open + + # Command drones to follow paths in a loop + def move_drones(): + while True: + for path in all_paths: + for point in path: + location = LocationGlobalRelative(point[0], point[1], 47) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(5) # Adjust this delay as necessary to maintain distance + + if all_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/AStar/test2.py b/PathPlanning/AStar/test2.py new file mode 100644 index 0000000000..88eec08e8c --- /dev/null +++ b/PathPlanning/AStar/test2.py @@ -0,0 +1,314 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function + +import math +import matplotlib.pyplot as plt +import matplotlib.animation as animation +import numpy as np +import argparse +import threading +import sys +import pathlib +import time +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil + +sys.path.append(str(pathlib.Path(__file__).parent)) + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +class AStarPlanner: + def __init__(self, ox, oy, resolution, rr): + self.resolution = resolution + self.rr = rr + self.min_x, self.min_y = 0, 0 + self.max_x, self.max_y = 0, 0 + self.obstacle_map = None + self.x_width, self.y_width = 0, 0 + self.motion = self.get_motion_model() + self.calc_obstacle_map(ox, oy) + + class Node: + def __init__(self, x, y, cost, parent_index): + self.x = x + self.y = y + self.cost = cost + self.parent_index = parent_index + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.parent_index) + + def planning(self, sx, sy, gx, gy): + start_node = self.Node(self.calc_xy_index(sx, self.min_x), self.calc_xy_index(sy, self.min_y), 0.0, -1) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), self.calc_xy_index(gy, self.min_y), 0.0, -1) + + open_set, closed_set = dict(), dict() + open_set[self.calc_grid_index(start_node)] = start_node + + path = [] + while True: + if len(open_set) == 0: + print("Open set is empty..") + break + + c_id = min(open_set, key=lambda o: open_set[o].cost + self.calc_heuristic(goal_node, open_set[o])) + current = open_set[c_id] + + if current.x == goal_node.x and current.y == goal_node.y: + print("Find goal") + goal_node.parent_index = current.parent_index + goal_node.cost = current.cost + path.append((self.calc_grid_position(goal_node.x, self.min_x), self.calc_grid_position(goal_node.y, self.min_y))) + break + + del open_set[c_id] + closed_set[c_id] = current + + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], current.cost + self.motion[i][2], c_id) + n_id = self.calc_grid_index(node) + + if not self.verify_node(node): + continue + + if n_id in closed_set: + continue + + if n_id not in open_set: + open_set[n_id] = node + else: + if open_set[n_id].cost > node.cost: + open_set[n_id] = node + + path.append((self.calc_grid_position(current.x, self.min_x), self.calc_grid_position(current.y, self.min_y))) + + # Animation + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current.x, self.min_x), + self.calc_grid_position(current.y, self.min_y), "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: + plt.pause(0.001) + + rx, ry = self.calc_final_path(goal_node, closed_set) + + # Final path plot + if show_animation: + plt.plot(rx, ry, "-r") + plt.pause(0.001) + return rx, ry, path + + def calc_final_path(self, goal_node, closed_set): + rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [self.calc_grid_position(goal_node.y, self.min_y)] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] + rx.append(self.calc_grid_position(n.x, self.min_x)) + ry.append(self.calc_grid_position(n.y, self.min_y)) + parent_index = n.parent_index + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, min_position): + pos = index * self.resolution + min_position + return pos + + def calc_xy_index(self, position, min_pos): + return round((position - min_pos) / self.resolution) + + def calc_grid_index(self, node): + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.min_x) + py = self.calc_grid_position(node.y, self.min_y) + + if px < self.min_x or py < self.min_y or px >= self.max_x or py >= self.max_y: + return False + + if self.obstacle_map[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + + self.obstacle_map = [[False for _ in range(self.y_width)] for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_grid_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_grid_position(iy, self.min_y) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obstacle_map[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + return motion + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def plot_destinations_and_fences(ax, start_position, destinations, fences): + ax.plot(start_position.lon, start_position.lat, 'bo', label="Start Position") + for dest in destinations: + loc = dest['location'] + ax.plot(loc.lon, loc.lat, 'go') + ax.text(loc.lon + 0.001, loc.lat + 0.001, dest['name'], fontsize=8, color='green') + for fence in fences: + ax.plot(fence['lon'], fence['lat'], 'ro') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.725, 0.4700, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + + + + + + + fences = [ + {'name': 'Fence 1', 'lat': 51.715, 'lon': 0.471500, 'radius': 0.0061477}, + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4655, 'radius': 0.004471}, + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448}, + {'name': 'Fence 4', 'lat': 51.72171, 'lon': 0.482, 'radius': 0.004471} + ] + + + fig2, ax = plt.subplots(figsize=(18, 18)) # Increase the figure size + plt.ion() # Turn on interactive mode + + plot_destinations_and_fences(ax, start_position, destinations, fences) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(0.46, 0.49) # Set x-axis limits + ax.set_ylim(51.68, 51.75) # Set y-axis limits + + ox = [f['lat'] for f in fences] + oy = [f['lon'] for f in fences] + + # ====Search Path with A*==== + # Parameter + grid_size = 0.0001 # 10 meters + robot_radius = 0.0005 # 5 meters + + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + a_star = AStarPlanner(ox, oy, grid_size, robot_radius) + rx, ry, path = a_star.planning(start[0], start[1], goal[0], goal[1]) + + if not path: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + all_paths.append(path) + + # Animate the paths + for path in all_paths: + x_data = [x for x, y in path] + y_data = [y for x, y in path] + ax.plot(x_data, y_data, "-r") + plt.pause(0.004) + plt.show() # Keep the plot open + + # Command drones to follow paths in a loop + def move_drones(): + while True: + for path in all_paths: + for point in path: + location = LocationGlobalRelative(point[0], point[1], 47) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(5) # Adjust this delay as necessary to maintain distance + + if all_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + +if __name__ == '__main__': + main() + From 61b0b0006750cdc7569438c3144e4b4203b2e08c Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:13:21 +0100 Subject: [PATCH 03/33] Add files via upload --- PathPlanning/RRT/test0.py | 252 ++++++++++++++++++++++++++++++++ PathPlanning/RRT/test1.py | 295 ++++++++++++++++++++++++++++++++++++++ PathPlanning/RRT/test2.py | 263 +++++++++++++++++++++++++++++++++ PathPlanning/RRT/test5.py | 179 +++++++++++++++++++++++ PathPlanning/RRT/test6.py | 184 ++++++++++++++++++++++++ 5 files changed, 1173 insertions(+) create mode 100644 PathPlanning/RRT/test0.py create mode 100644 PathPlanning/RRT/test1.py create mode 100644 PathPlanning/RRT/test2.py create mode 100644 PathPlanning/RRT/test5.py create mode 100644 PathPlanning/RRT/test6.py diff --git a/PathPlanning/RRT/test0.py b/PathPlanning/RRT/test0.py new file mode 100644 index 0000000000..590b896590 --- /dev/null +++ b/PathPlanning/RRT/test0.py @@ -0,0 +1,252 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function + +import time +import math +import sys +import pathlib +import threading +import matplotlib.pyplot as plt +import numpy as np +import argparse +import random +import matplotlib.animation as animation +sys.path.append(str(pathlib.Path(__file__).parent)) + +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from rrt import RRT + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.7106, 0.4800, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.0041477}, # Approx 530 meters + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, # Approx 525 meters + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00648} # Approx 500 meters + ] + + fig, ax = plt.subplots(figsize=(12, 12)) # Increase the figure size + + # Draw obstacles (fences) + for fence in fences: + circle = plt.Circle((fence['lat'], fence['lon']), fence['radius'], color='r', fill=False) + ax.add_artist(circle) + + # Draw start position and destinations + ax.plot(start_position.lat, start_position.lon, 'bo', label="Start Position") + for destination in destinations: + ax.plot(destination['location'].lat, destination['location'].lon, 'go', label=destination['name']) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(51.7, 51.74) # Set x-axis limits + ax.set_ylim(0.47, 0.49) # Set y-axis limits + + # ====Search Path with RRT==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_smoothed_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + rrt = RRT(start=start, goal=goal, rand_area=[-2, 15], obstacle_list=obstacleList) + path = rrt.planning(animation=show_animation) + + if path is None: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + # Path smoothing + maxIter = 3000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + all_smoothed_paths.append(smoothedPath) + + # Function to update the plot + def update(num, data, line): + line.set_data(data[:, :num]) + return line, + time.sleep(10) + ani_list = [] + time.sleep(10) + for smoothedPath in all_smoothed_paths: + # Draw final path + if show_animation and smoothedPath: + x_data = np.array([x for (x, y) in smoothedPath]) + y_data = np.array([y for (x, y) in smoothedPath]) + data = np.vstack((x_data, y_data)) + + line, = ax.plot([], [], '-c', label="Smoothed Path") + ani = animation.FuncAnimation(fig, update, frames=len(x_data), fargs=(data, line), blit=True) + ani_list.append(ani) + + plt.grid(True) + plt.pause(0.01) # Need for Mac + time.sleep(10) + plt.show() # Keep the plot open + + # Command drones to follow smoothed paths in a loop + def move_drones(): + while True: + for smoothedPath in all_smoothed_paths: + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 37) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(10) # Adjust this delay as necessary to maintain distance + + if all_smoothed_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/RRT/test1.py b/PathPlanning/RRT/test1.py new file mode 100644 index 0000000000..4ff411b098 --- /dev/null +++ b/PathPlanning/RRT/test1.py @@ -0,0 +1,295 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function + +import time +import math +import sys +import pathlib +import threading +import matplotlib.pyplot as plt +import numpy as np +import argparse +import random +import matplotlib.animation as animation +sys.path.append(str(pathlib.Path(__file__).parent)) + +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from rrt import RRT + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def plot_destinations_and_fences(ax, destinations, fences): + for dest in destinations: + loc = dest['location'] + ax.scatter(loc.lon, loc.lat, color='blue', marker='o') + ax.text(loc.lon + 0.001, loc.lat + 0.001, dest['name'], fontsize=8, color='blue') + for fence in fences: + ax.scatter(fence['lon'], fence['lat'], color='red', marker='o') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +''' +def update_rrt_path(ax, drone_paths): + ax.clear() + plot_destinations_and_fences(ax, destinations, fences) + for i, path in enumerate(drone_paths): + if path: + path_lons = [point.lon for point in path] + path_lats = [point.lat for point in path] + ax.plot(path_lons, path_lats, linestyle='-', marker='o', label=f'Drone {i+1} Path') + # Add a dummy plot for the legend if no paths are present + if not drone_paths: + ax.plot([], [], label='No Path Available') # This prevents the legend from being empty + ax.legend() + ax.set_xlabel('Longitude') + ax.set_ylabel('Latitude') + ax.set_title('Real-time RRT Path Visualization') + ax.grid(True) + plt.draw() + plt.pause(0.1) + +''' +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.7106, 0.4800, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.0031477}, # Approx 530 meters + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, # Approx 525 meters + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448} # Approx 500 meters + ] + + fig, ax = plt.subplots(figsize=(10, 10)) # Increase the figure size + plt.ion() # Turn on interactive mode + fig2, ax1 = plt.subplots(figsize=(10, 8)) + + plot_destinations_and_fences(ax1, destinations, fences) + ax1.legend() + plt.show() + # Draw obstacles (fences) + for fence in fences: + circle = plt.Circle((fence['lat'], fence['lon']), fence['radius'], color='r', fill=False) + ax.add_artist(circle) + + # Draw start position and destinations + ax.plot(start_position.lat, start_position.lon, 'bo', label="Start Position") + for destination in destinations: + ax.plot(destination['location'].lat, destination['location'].lon, 'go', label=destination['name']) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(51.68, 51.75) # Set x-axis limits + ax.set_ylim(0.46, 0.49) # Set y-axis limits + + # ====Search Path with RRT==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_smoothed_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + rrt = RRT(start=start, goal=goal, rand_area=[-2, 15], obstacle_list=obstacleList) + path = rrt.planning(animation=show_animation) + + if path is None: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + # Path smoothing + maxIter = 3000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + all_smoothed_paths.append(smoothedPath) + + # Function to update the plot + def update(num, data, line): + line.set_data(data[:, :num]) + return line, + + ani_list = [] + + for smoothedPath in all_smoothed_paths: + # Draw final path + if show_animation and smoothedPath: + x_data = np.array([x for (x, y) in smoothedPath]) + y_data = np.array([y for (x, y) in smoothedPath]) + data = np.vstack((x_data, y_data)) + + print(f"Smoothed Path Data: {data}") # Debugging print statement + + line, = ax.plot([], [], '-c', label="Smoothed Path") + ani = animation.FuncAnimation(fig, update, frames=len(x_data), fargs=(data, line), blit=True) + ani_list.append(ani) + + plt.grid(True) + plt.pause(0.01) # Need for Mac + + plt.show() # Keep the plot open + + + # Command drones to follow smoothed paths in a loop + def move_drones(): + while True: + for smoothedPath in all_smoothed_paths: + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 47) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(5) # Adjust this delay as necessary to maintain distance + + if all_smoothed_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + + + + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/RRT/test2.py b/PathPlanning/RRT/test2.py new file mode 100644 index 0000000000..2e60776706 --- /dev/null +++ b/PathPlanning/RRT/test2.py @@ -0,0 +1,263 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function + +import time +import math +import sys +import pathlib +import threading +import matplotlib.pyplot as plt +import numpy as np +import argparse +import random +import matplotlib.animation as animation +sys.path.append(str(pathlib.Path(__file__).parent)) + +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from rrt import RRT + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def plot_destinations_and_fences(ax, start_position, destinations, fences): + ax.plot(start_position.lon, start_position.lat, 'bo', label="Start Position") + for dest in destinations: + loc = dest['location'] + ax.plot(loc.lon, loc.lat, 'go') + ax.text(loc.lon + 0.001, loc.lat + 0.001, dest['name'], fontsize=8, color='green') + for fence in fences: + ax.plot(fence['lon'], fence['lat'], 'ro') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.71506, 0.461, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.731, 0.462, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.0031477}, + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.0041471}, + {'name': 'Fence 2', 'lat': 51.715071, 'lon': 0.4858, 'radius': 0.0041471}, + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.465, 'radius': 0.00448} + ] + + fig, ax = plt.subplots(figsize=(10, 10)) # Increase the figure size + plt.ion() # Turn on interactive mode + + plot_destinations_and_fences(ax, start_position, destinations, fences) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(0.46, 0.49) # Set x-axis limits + ax.set_ylim(51.68, 51.75) # Set y-axis limits + + # ====Search Path with RRT==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + fig2, ax1 = plt.subplots(figsize=(12, 12)) + + ax1.legend() + plt.show() + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_smoothed_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + rrt = RRT(start=start, goal=goal, rand_area=[-2, 15], obstacle_list=obstacleList) + path = rrt.planning(animation=show_animation) + + if path is None: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + # Path smoothing + maxIter = 3000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + all_smoothed_paths.append(smoothedPath) + + # Function to update the plot + def update(num, data, line): + line.set_data(data[:, :num]) + return line, + + ani_list = [] + + for smoothedPath in all_smoothed_paths: + # Draw final path + if show_animation and smoothedPath: + x_data = np.array([x for (x, y) in smoothedPath]) + y_data = np.array([y for (x, y) in smoothedPath]) + data = np.vstack((x_data, y_data)) + + print(f"Smoothed Path Data: {data}") # Debugging print statement + + line, = ax.plot([], [], '-c', label="Smoothed Path") + ani = animation.FuncAnimation(fig, update, frames=len(x_data), fargs=(data, line), blit=True) + ani_list.append(ani) + + plt.grid(True) + plt.pause(0.01) # Need for Mac + + plt.show() # Keep the plot open + + # Command drones to follow smoothed paths in a loop + def move_drones(): + while True: + for smoothedPath in all_smoothed_paths: + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 47) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(5) # Adjust this delay as necessary to maintain distance + + if all_smoothed_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/RRT/test5.py b/PathPlanning/RRT/test5.py new file mode 100644 index 0000000000..f6032c8957 --- /dev/null +++ b/PathPlanning/RRT/test5.py @@ -0,0 +1,179 @@ +""" +Path planning Sample Code with RRT with path smoothing + +@author: AtsushiSakai(@Atsushi_twi) +""" + +import math +import random +import matplotlib.pyplot as plt +import sys +import pathlib +import argparse +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil + +sys.path.append(str(pathlib.Path(__file__).parent)) + +from rrt import RRT + +show_animation = True + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def connect_vehicle(connection_string): + print('Connecting to vehicle on:', connection_string) + return connect(connection_string, wait_ready=True) + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +def main(): + parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') + parser.add_argument('--connect1', help="Vehicle 1 connection target string.") + parser.add_argument('--connect2', help="Vehicle 2 connection target string.") + args = parser.parse_args() + + connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' + connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + + vehicle1 = connect_vehicle(connection_string1) + vehicle2 = connect_vehicle(connection_string2) + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.7106, 0.4800, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.0081477}, # Approx 530 meters + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, # Approx 525 meters + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00648} # Approx 500 meters + ] + + # ====Search Path with RRT==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + rrt = RRT(start=[0, 0], goal=[6, 10], + rand_area=[-2, 15], obstacle_list=obstacleList) + path = rrt.planning(animation=show_animation) + + # Path smoothing + maxIter = 1000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + + # Draw final path + if show_animation: + rrt.draw_graph() + plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') + + plt.plot([x for (x, y) in smoothedPath], [ + y for (x, y) in smoothedPath], '-c') + + plt.grid(True) + plt.pause(0.01) # Need for Mac + plt.show() + + # Command drones to follow smoothed path + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 10) # Example altitude + vehicle1.simple_goto(location) + vehicle2.simple_goto(location) + # Add delay or monitoring code here if necessary + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/RRT/test6.py b/PathPlanning/RRT/test6.py new file mode 100644 index 0000000000..38bb9b04f8 --- /dev/null +++ b/PathPlanning/RRT/test6.py @@ -0,0 +1,184 @@ +""" +Path planning Sample Code with RRT with path smoothing + +@author: AtsushiSakai(@Atsushi_twi) +""" + +import math +import random +import matplotlib.pyplot as plt +import sys +import pathlib +import argparse +import time +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil + +sys.path.append(str(pathlib.Path(__file__).parent)) + +from rrt import RRT + +show_animation = True + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def connect_vehicle(connection_string): + print('Connecting to vehicle on:', connection_string) + return connect(connection_string, wait_ready=True) + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +def main(): + parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') + parser.add_argument('--connect1', help="Vehicle 1 connection target string.") + parser.add_argument('--connect2', help="Vehicle 2 connection target string.") + args = parser.parse_args() + + connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' + connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + + vehicle1 = connect_vehicle(connection_string1) + vehicle2 = connect_vehicle(connection_string2) + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.7106, 0.4800, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.001477}, # Approx 530 meters + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, # Approx 525 meters + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448} # Approx 500 meters + #{'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, # Approx 525 meters + #{'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448} # Approx 500 meters + ] + + # ====Search Path with RRT==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + rrt = RRT(start=[51.73, 0.483], goal=[51.7106, 0.4800], + rand_area=[-50, 52], obstacle_list=obstacleList) + path = rrt.planning(animation=show_animation) + + # Path smoothing + maxIter = 3000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + + # Draw final path + if show_animation: + rrt.draw_graph() + plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') + + plt.plot([x for (x, y) in smoothedPath], [ + y for (x, y) in smoothedPath], '-c') + + plt.grid(True) + plt.pause(0.01) # Need for Mac + plt.show() + + # Command drones to follow smoothed path + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 10) # Example altitude + vehicle2.simple_goto(location) + time.sleep(2) # Delay to ensure vehicle 1 moves first + vehicle1.simple_goto(location) + time.sleep(2) # Adjust this delay as necessary to maintain distance + +if __name__ == '__main__': + main() + From 9b7366dd83c4d48cc82653bf6c3f798849195d70 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:13:57 +0100 Subject: [PATCH 04/33] Add files via upload --- PathPlanning/RRTStar/test22.py | 259 +++++++++++++++++++++++++++++++++ PathPlanning/RRTStar/test3.py | 78 ++++++++++ 2 files changed, 337 insertions(+) create mode 100644 PathPlanning/RRTStar/test22.py create mode 100644 PathPlanning/RRTStar/test3.py diff --git a/PathPlanning/RRTStar/test22.py b/PathPlanning/RRTStar/test22.py new file mode 100644 index 0000000000..0696a83faa --- /dev/null +++ b/PathPlanning/RRTStar/test22.py @@ -0,0 +1,259 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function + +import time +import math +import sys +import pathlib +import threading +import matplotlib.pyplot as plt +import numpy as np +import argparse +import random +import matplotlib.animation as animation +sys.path.append(str(pathlib.Path(__file__).parent)) + +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from rrt_star import RRTStar # Import RRTStar from the module + +show_animation = True +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +def set_parameter_value(vehicle, parameter, value): + msg = vehicle.message_factory.param_set_encode( + 0, # Target system (0 for broadcast) + 0, # Target component (0 for broadcast) + parameter.encode('utf-8'), # Parameter name as a byte string + float(value), # Parameter value + mavutil.mavlink.MAV_PARAM_TYPE_REAL32 # Parameter type + ) + vehicle.send_mavlink(msg) + vehicle.flush() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +print('Connecting to vehicle on:', connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on:', connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +def get_path_length(path): + le = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + + return le + +def get_target_point(path, targetL): + le = 0 + ti = 0 + lastPairLen = 0 + for i in range(len(path) - 1): + dx = path[i + 1][0] - path[i][0] + dy = path[i + 1][1] - path[i][1] + d = math.hypot(dx, dy) + le += d + if le >= targetL: + ti = i - 1 + lastPairLen = d + break + + partRatio = (le - targetL) / lastPairLen + + x = path[ti][0] + (path[ti + 1][0] - path[ti][0]) * partRatio + y = path[ti][1] + (path[ti + 1][1] - path[ti][1]) * partRatio + + return [x, y, ti] + +def line_collision_check(first, second, obstacleList): + # Line Equation + x1 = first[0] + y1 = first[1] + x2 = second[0] + y2 = second[1] + + try: + a = y2 - y1 + b = -(x2 - x1) + c = y2 * (x2 - x1) - x2 * (y2 - y1) + except ZeroDivisionError: + return False + + for (ox, oy, size) in obstacleList: + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) + if d <= size: + return False + + return True # OK + +def path_smoothing(path, max_iter, obstacle_list): + le = get_path_length(path) + + for i in range(max_iter): + # Sample two points + pickPoints = [random.uniform(0, le), random.uniform(0, le)] + pickPoints.sort() + first = get_target_point(path, pickPoints[0]) + second = get_target_point(path, pickPoints[1]) + + if first[2] <= 0 or second[2] <= 0: + continue + + if (second[2] + 1) > len(path): + continue + + if second[2] == first[2]: + continue + + # collision check + if not line_collision_check(first, second, obstacle_list): + continue + + # Create New path + newPath = [] + newPath.extend(path[:first[2] + 1]) + newPath.append([first[0], first[1]]) + newPath.append([second[0], second[1]]) + newPath.extend(path[second[2] + 1:]) + path = newPath + le = get_path_length(path) + + return path + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def follow_leader(follower, leader, follow_distance=5): + while True: + leader_location = leader.location.global_relative_frame + follow_location = get_location_offset(leader_location, -follow_distance, 0) # Follow behind the leader + print(f"Follower moving to: {follow_location}") + follower.simple_goto(follow_location) + time.sleep(1) + +def plot_destinations_and_fences(ax, start_position, destinations, fences): + ax.plot(start_position.lon, start_position.lat, 'bo', label="Start Position") + for dest in destinations: + loc = dest['location'] + ax.plot(loc.lon, loc.lat, 'go') + ax.text(loc.lon + 0.001, loc.lat + 0.001, dest['name'], fontsize=8, color='green') + for fence in fences: + ax.plot(fence['lon'], fence['lat'], 'ro') + circle = plt.Circle((fence['lon'], fence['lat']), fence['radius'], color='red', fill=False) + ax.add_artist(circle) + ax.text(fence['lon'] + 0.001, fence['lat'] + 0.001, fence['name'] + ' Fence', fontsize=8, color='red') + +def main(): + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for vehicle 2 + + destinations = [ + {'name': 'Destination 1', 'location': LocationGlobalRelative(51.70715, 0.482, 37)}, + {'name': 'Destination 2', 'location': LocationGlobalRelative(51.7106, 0.4800, 56)}, + {'name': 'Destination 3', 'location': LocationGlobalRelative(51.7359071, 0.4732, 33)} + ] + + fences = [ + {'name': 'Fence 1', 'lat': 51.71106, 'lon': 0.47100, 'radius': 0.0031477}, + {'name': 'Fence 2', 'lat': 51.719071, 'lon': 0.4772688, 'radius': 0.001471}, + {'name': 'Fence 3', 'lat': 51.725, 'lon': 0.485, 'radius': 0.00448} + ] + + fig, ax = plt.subplots(figsize=(14, 14)) # Increase the figure size + plt.ion() # Turn on interactive mode + + plot_destinations_and_fences(ax, start_position, destinations, fences) + + ax.legend() + ax.set_aspect('equal') # Set aspect ratio to be equal + ax.set_xlim(0.46, 0.49) # Set x-axis limits + ax.set_ylim(51.68, 51.75) # Set y-axis limits + + # ====Search Path with RRT*==== + # Parameter + obstacleList = [(f['lat'], f['lon'], f['radius']) for f in fences] + + # Add a path for the drone to follow from start_position to each destination + waypoints = [start_position] + [d['location'] for d in destinations] + + all_smoothed_paths = [] + + for i in range(len(waypoints) - 1): + start = [waypoints[i].lat, waypoints[i].lon] + goal = [waypoints[i + 1].lat, waypoints[i + 1].lon] + rrt_star = RRTStar(start=start, goal=goal, rand_area=[-2, 15], obstacle_list=obstacleList) + path = rrt_star.planning(animation=show_animation) + + if path is None: + print(f"Path planning failed from {start} to {goal}") + continue + else: + print(f"Path found from {start} to {goal}") + + # Path smoothing + maxIter = 3000 + smoothedPath = path_smoothing(path, maxIter, obstacleList) + all_smoothed_paths.append(smoothedPath) + + # Function to update the plot + def update(num, data, line): + line.set_data(data[:, :num]) + return line, + + ani_list = [] + + for smoothedPath in all_smoothed_paths: + # Draw final path + if show_animation and smoothedPath: + x_data = np.array([x for (x, y) in smoothedPath]) + y_data = np.array([y for (x, y) in smoothedPath]) + data = np.vstack((x_data, y_data)) + + print(f"Smoothed Path Data: {data}") # Debugging print statement + + line, = ax.plot([], [], '-c', label="Smoothed Path") + ani = animation.FuncAnimation(fig, update, frames=len(x_data), fargs=(data, line), blit=True) + ani_list.append(ani) + + plt.grid(True) + plt.pause(0.01) # Need for Mac + + plt.show() # Keep the plot open + + # Command drones to follow smoothed paths in a loop + def move_drones(): + while True: + for smoothedPath in all_smoothed_paths: + for point in smoothedPath: + location = LocationGlobalRelative(point[0], point[1], 47) # Example altitude + print(f"Leader moving to: {location}") + vehicle2.simple_goto(location) + time.sleep(5) # Adjust this delay as necessary to maintain distance + + if all_smoothed_paths: + follower_thread = threading.Thread(target=follow_leader, args=(vehicle1, vehicle2)) + follower_thread.daemon = True + follower_thread.start() + + move_drones_thread = threading.Thread(target=move_drones) + move_drones_thread.start() + +if __name__ == '__main__': + main() + diff --git a/PathPlanning/RRTStar/test3.py b/PathPlanning/RRTStar/test3.py new file mode 100644 index 0000000000..7a979b2cca --- /dev/null +++ b/PathPlanning/RRTStar/test3.py @@ -0,0 +1,78 @@ +import heapq +import math + +class AStar: + class Node: + def __init__(self, x, y, cost, parent): + self.x = x + self.y = y + self.cost = cost + self.parent = parent + self.f_cost = 0.0 # Total cost (g_cost + h_cost) + + def __lt__(self, other): + return self.f_cost < other.f_cost + + def __init__(self, start, goal, obstacle_list, grid_size, robot_radius): + self.start = self.Node(start[0], start[1], 0.0, None) + self.goal = self.Node(goal[0], goal[1], 0.0, None) + self.obstacle_list = obstacle_list + self.grid_size = grid_size + self.robot_radius = robot_radius + self.motion = self.get_motion_model() + + def planning(self): + open_list = [] + closed_list = set() + heapq.heappush(open_list, self.start) + + while open_list: + current = heapq.heappop(open_list) + closed_list.add((current.x, current.y)) + + if self.is_goal(current): + return self.extract_path(current) + + for move_x, move_y, move_cost in self.motion: + node = self.Node(current.x + move_x, current.y + move_y, current.cost + move_cost, current) + node.f_cost = node.cost + self.heuristic(node, self.goal) + + if (node.x, node.y) in closed_list or not self.is_free(node): + continue + + heapq.heappush(open_list, node) + + return None + + def extract_path(self, node): + path = [[node.x, node.y]] + while node.parent is not None: + node = node.parent + path.append([node.x, node.y]) + path.reverse() + return path + + def is_goal(self, node): + return self.calc_distance(node, self.goal) <= self.grid_size + + def is_free(self, node): + for (ox, oy, size) in self.obstacle_list: + if math.hypot(ox - node.x, oy - node.y) <= size + self.robot_radius: + return False + return True + + def calc_distance(self, node1, node2): + return math.hypot(node2.x - node1.x, node2.y - node1.y) + + def heuristic(self, node1, node2): + return self.calc_distance(node1, node2) + + @staticmethod + def get_motion_model(): + # dx, dy, cost + return [ + (1, 0, 1), (0, 1, 1), (-1, 0, 1), (0, -1, 1), + (-1, -1, math.sqrt(2)), (-1, 1, math.sqrt(2)), + (1, -1, math.sqrt(2)), (1, 1, math.sqrt(2)) + ] + From e58086343bb54a91c2f5da3033585dc23dcb3767 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:20:29 +0100 Subject: [PATCH 05/33] Add files via upload --- settings.json | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 settings.json diff --git a/settings.json b/settings.json new file mode 100644 index 0000000000..fd1383b806 --- /dev/null +++ b/settings.json @@ -0,0 +1,31 @@ +{ + "SettingsVersion": 1.2, + "SimMode": "Multirotor", + "OriginGeopoint": { + "Latitude": 51.77458, + "Longitude": 0.46677, + "Altitude": 56 + }, + "Vehicles": { + "Copter1": { + "VehicleType": "ArduCopter", + "UseSerial": false, + "LocalHostIp": "127.0.0.1", + "UdpIp": "127.0.0.1", + "UdpPort": 9003, + "ControlPort": 9002 + }, + "Copter2": { + "VehicleType": "ArduCopter", + "UseSerial": false, + "LocalHostIp": "127.0.0.1", + "UdpIp": "127.0.0.1", + "UdpPort": 9013, + "ControlPort": 9012, + "X": 0, + "Y": 3, + "Z": 0 + } + } +} + From 989541d14c84a09ef574714d94592b5c4bac4ed0 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:31:11 +0100 Subject: [PATCH 06/33] Update README.md Airsim, Unreal, Drone Kit, Drone Kit SITL, Shapely and Ardupilot --- README.md | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/README.md b/README.md index ee40dfc7eb..24a0038e9b 100644 --- a/README.md +++ b/README.md @@ -75,6 +75,20 @@ Python codes for robotics algorithm. * [Authors](#authors) # What is this? +1. Copy the settings.json file in this repository into your Documents/AirSim folder. +2. Run the ./libraries/SITL/examples/Airsim/follow-1-copter.sh in the Terminal +3. Download the Takeoff_arm.py located in the Python_Code folder of this repository. Run the script to make the drones go into the Guided mode, Arm and Takeoff, and make sure MavProxy for both drones is running. +4. Install the following: +sudo pip install shapely +sudo pip install dronekit +pip install dronekit-sitl +5. Install the AirSim and Unreal 4.7 +6. Run the Blocks.uproject located in the Unreal folder of Airsim. + + + +# What is this? + This is a Python code collection of robotics algorithms. From cf6d5a05958031ec3f4ed238e6c51e39ce9623d9 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:42:11 +0100 Subject: [PATCH 07/33] Add files via upload --- Takeoff_arm.py | 70 ++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) create mode 100644 Takeoff_arm.py diff --git a/Takeoff_arm.py b/Takeoff_arm.py new file mode 100644 index 0000000000..ee3a5659db --- /dev/null +++ b/Takeoff_arm.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +""" +© Copyright 2015-2016, 3D Robotics. +guided_set_speed_yaw.py: (Copter Only) +This example shows how to move/direct Copter and send commands in GUIDED mode using DroneKit Python. +Example documentation: http://python.dronekit.io/examples/guided-set-speed-yaw-demo.html +""" +from __future__ import print_function +import numpy as np +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil +import time +import math +import threading +import matplotlib.pyplot as plt +import argparse +from mpl_toolkits.mplot3d import Axes3D + +# Set up option parsing to get connection string +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +# Connect to the Vehicles +print('Connecting to vehicle on: %s' % connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on: %s' % connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +# Function to arm and takeoff +def arm_and_takeoff(vehicle, aTargetAltitude): + """ + Arms vehicle and fly to aTargetAltitude. + """ + # time.sleep(1) + + print("Arming motors") + vehicle.mode = VehicleMode("GUIDED") + time.sleep(3) + vehicle.armed = True + + + print("Taking off!") + vehicle.simple_takeoff(aTargetAltitude) + # while True: + print(f" Altitude: {vehicle.location.global_relative_frame.alt}") + # if vehicle.location.global_relative_frame.alt >= aTargetAltitude * 0.95: + print("Reached target altitude") + # break + time.sleep(3) + + + +# Arm and take off to altitude of 5 meters for both vehicles +arm_and_takeoff(vehicle1, 5) +time.sleep(10) # Wait for some time to ensure vehicle1 has taken off +arm_and_takeoff(vehicle2, 5) +time.sleep(15) +print("Both vehicles are in the air.") +current_value1 = vehicle1.parameters['WPNAV_SPEED_UP'] +current_value2 = vehicle2.parameters['WPNAV_SPEED_UP'] +print(f"WPNAV_SPEED_UP parameter set to: {current_value1} for vehicle 1") +print(f"WPNAV_SPEED_UP parameter set to: {current_value2} for vehicle 2") + From dee3bfa05eb31b9029d13c8f9e00a09ce96d4fd4 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:44:11 +0100 Subject: [PATCH 08/33] Update README.md --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 24a0038e9b..b583d39c2a 100644 --- a/README.md +++ b/README.md @@ -74,10 +74,10 @@ Python codes for robotics algorithm. * [1Password](#1password) * [Authors](#authors) -# What is this? +# How to use it with Ardupilot, AirSim and Unreal 4.7 1. Copy the settings.json file in this repository into your Documents/AirSim folder. 2. Run the ./libraries/SITL/examples/Airsim/follow-1-copter.sh in the Terminal -3. Download the Takeoff_arm.py located in the Python_Code folder of this repository. Run the script to make the drones go into the Guided mode, Arm and Takeoff, and make sure MavProxy for both drones is running. +3. Download the Takeoff_arm.py in this repository. Run the script to make the drones go into Guided mode, Arm, and Takeoff, and make sure MavProxy for both drones is running. 4. Install the following: sudo pip install shapely sudo pip install dronekit From 739f2bf3e6d28c420f665ab7cea5c8deea9ae3ed Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:47:37 +0100 Subject: [PATCH 09/33] Update README.md --- README.md | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index b583d39c2a..b4416ae7c1 100644 --- a/README.md +++ b/README.md @@ -75,17 +75,23 @@ Python codes for robotics algorithm. * [Authors](#authors) # How to use it with Ardupilot, AirSim and Unreal 4.7 -1. Copy the settings.json file in this repository into your Documents/AirSim folder. -2. Run the ./libraries/SITL/examples/Airsim/follow-1-copter.sh in the Terminal -3. Download the Takeoff_arm.py in this repository. Run the script to make the drones go into Guided mode, Arm, and Takeoff, and make sure MavProxy for both drones is running. +1. Install the AirSim and Unreal 4.7 +2. Copy the settings.json file in this repository into your Documents/AirSim folder. +3. Run the Blocks.uproject located in the Unreal folder of Airsim. + + 4. Install the following: + sudo pip install shapely + sudo pip install dronekit + pip install dronekit-sitl -5. Install the AirSim and Unreal 4.7 -6. Run the Blocks.uproject located in the Unreal folder of Airsim. +5. Run the ./libraries/SITL/examples/Airsim/follow-1-copter.sh in the Terminal +6. Download the Takeoff_arm.py in this repository. Run the script to make the drones go into Guided mode, Arm, and Takeoff, and make sure MavProxy for both drones is running. + # What is this? From 22c43f4c5b0578cbd42e69cb07392b636a77c76a Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 30 Jun 2024 10:48:35 +0100 Subject: [PATCH 10/33] Update README.md --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index b4416ae7c1..3363e3b6a4 100644 --- a/README.md +++ b/README.md @@ -74,7 +74,9 @@ Python codes for robotics algorithm. * [1Password](#1password) * [Authors](#authors) -# How to use it with Ardupilot, AirSim and Unreal 4.7 +# How to use it with repository: Ardupilot, AirSim and Unreal 4.7 + +git clone https://github.com/ss48/PythonRobotics_AirSim_Unreal.git 1. Install the AirSim and Unreal 4.7 2. Copy the settings.json file in this repository into your Documents/AirSim folder. 3. Run the Blocks.uproject located in the Unreal folder of Airsim. From aa3f511283668ffe5e67c1d8c667dd16213cbe3c Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Tue, 2 Jul 2024 09:11:17 +0100 Subject: [PATCH 11/33] Add files via upload --- PathPlanning/DynamicWindowApproach/dwa.py | 151 ++++++++++++++++++++++ 1 file changed, 151 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/dwa.py diff --git a/PathPlanning/DynamicWindowApproach/dwa.py b/PathPlanning/DynamicWindowApproach/dwa.py new file mode 100644 index 0000000000..c7a802d86b --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/dwa.py @@ -0,0 +1,151 @@ +import math +import numpy as np +from enum import Enum +import matplotlib.pyplot as plt + +class RobotType(Enum): + circle = 0 + rectangle = 1 + +class Config: + def __init__(self): + self.max_speed = 1.0 # [m/s] + self.min_speed = -0.5 # [m/s] + self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s] + self.max_accel = 0.2 # [m/ss] + self.max_delta_yaw_rate = 40.0 * math.pi / 180.0 # [rad/ss] + self.v_resolution = 0.01 # [m/s] + self.yaw_rate_resolution = 0.1 * math.pi / 180.0 # [rad/s] + self.dt = 0.1 # [s] Time tick for motion prediction + self.predict_time = 3.0 # [s] + self.to_goal_cost_gain = 0.15 + self.speed_cost_gain = 1.0 + self.obstacle_cost_gain = 1.0 + self.robot_stuck_flag_cons = 0.001 # constant to prevent robot stucked + self.robot_type = RobotType.circle + self.robot_radius = 1.0 # [m] for collision check + self.robot_width = 0.5 # [m] for collision check + self.robot_length = 1.2 # [m] for collision check + self.ob = np.array([[51.74531, 0.47058], [51.73484, 0.45986], [51.715071, 0.4858], [51.75032, 0.48405], [51.74856, 0.48624], [51.73793, 0.48606], [51.76216, 0.47748], [51.76928, 0.46855]]) # Initialize with empty array + + @property + def robot_type(self): + return self._robot_type + + @robot_type.setter + def robot_type(self, value): + if not isinstance(value, RobotType): + raise TypeError("robot_type must be an instance of RobotType") + self._robot_type = value + +def motion(x, u, dt): + x[2] += u[1] * dt + x[0] += u[0] * math.cos(x[2]) * dt + x[1] += u[0] * math.sin(x[2]) * dt + x[3] = u[0] + x[4] = u[1] + return x + +def dwa_control(x, config, goal, ob): + dw = calc_dynamic_window(x, config) + u, trajectory = calc_control_and_trajectory(x, dw, config, goal, ob) + return u, trajectory + +def calc_dynamic_window(x, config): + Vs = [config.min_speed, config.max_speed, + -config.max_yaw_rate, config.max_yaw_rate] + Vd = [x[3] - config.max_accel * config.dt, + x[3] + config.max_accel * config.dt, + x[4] - config.max_delta_yaw_rate * config.dt, + x[4] + config.max_delta_yaw_rate * config.dt] + dw = [max(Vs[0], Vd[0]), min(Vs[1], Vd[1]), + max(Vs[2], Vd[2]), min(Vs[3], Vd[3])] + return dw + +def predict_trajectory(x_init, v, y, config): + x = np.array(x_init) + trajectory = np.array(x) + time = 0 + while time <= config.predict_time: + x = motion(x, [v, y], config.dt) + trajectory = np.vstack((trajectory, x)) + time += config.dt + return trajectory + +def calc_control_and_trajectory(x, dw, config, goal, ob): + x_init = x[:] + min_cost = float("inf") + best_u = [0.0, 0.0] + best_trajectory = np.array([x]) + for v in np.arange(dw[0], dw[1], config.v_resolution): + for y in np.arange(dw[2], dw[3], config.yaw_rate_resolution): + trajectory = predict_trajectory(x_init, v, y, config) + to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(trajectory, goal) + speed_cost = config.speed_cost_gain * (config.max_speed - trajectory[-1, 3]) + ob_cost = config.obstacle_cost_gain * calc_obstacle_cost(trajectory, ob, config) + final_cost = to_goal_cost + speed_cost + ob_cost + if min_cost >= final_cost: + min_cost = final_cost + best_u = [v, y] + best_trajectory = trajectory + if abs(best_u[0]) < config.robot_stuck_flag_cons and abs(x[3]) < config.robot_stuck_flag_cons: + best_u[1] = -config.max_delta_yaw_rate + return best_u, best_trajectory + +def calc_obstacle_cost(trajectory, ob, config): + ox = ob[:, 0] + oy = ob[:, 1] + dx = trajectory[:, 0] - ox[:, None] + dy = trajectory[:, 1] - oy[:, None] + r = np.hypot(dx, dy) + if config.robot_type == RobotType.rectangle: + yaw = trajectory[:, 2] + rot = np.array([[np.cos(yaw), -np.sin(yaw)], [np.sin(yaw), np.cos(yaw)]]) + rot = np.transpose(rot, [2, 0, 1]) + local_ob = ob[:, None] - trajectory[:, 0:2] + local_ob = local_ob.reshape(-1, local_ob.shape[-1]) + local_ob = np.array([local_ob @ x for x in rot]) + local_ob = local_ob.reshape(-1, local_ob.shape[-1]) + upper_check = local_ob[:, 0] <= config.robot_length / 2 + right_check = local_ob[:, 1] <= config.robot_width / 2 + bottom_check = local_ob[:, 0] >= -config.robot_length / 2 + left_check = local_ob[:, 1] >= -config.robot_width / 2 + if (np.logical_and(np.logical_and(upper_check, right_check), + np.logical_and(bottom_check, left_check))).any(): + return float("Inf") + elif config.robot_type == RobotType.circle: + if np.array(r <= config.robot_radius).any(): + return float("Inf") + min_r = np.min(r) + return 1.0 / min_r + +def calc_to_goal_cost(trajectory, goal): + dx = goal[0] - trajectory[-1, 0] + dy = goal[1] - trajectory[-1, 1] + error_angle = math.atan2(dy, dx) + cost_angle = error_angle - trajectory[-1, 2] + cost = abs(math.atan2(math.sin(cost_angle), math.cos(cost_angle))) + return cost + +def plot_robot(x, y, yaw, config): + if config.robot_type == RobotType.rectangle: + outline = np.array([[-config.robot_length / 2, config.robot_length / 2, + (config.robot_length / 2), -config.robot_length / 2, + -config.robot_length / 2], + [config.robot_width / 2, config.robot_width / 2, + - config.robot_width / 2, -config.robot_width / 2, + config.robot_width / 2]]) + Rot1 = np.array([[math.cos(yaw), math.sin(yaw)], + [-math.sin(yaw), math.cos(yaw)]]) + outline = (outline.T.dot(Rot1)).T + outline[0, :] += x + outline[1, :] += y + plt.plot(np.array(outline[0, :]).flatten(), + np.array(outline[1, :]).flatten(), "-k") + elif config.robot_type == RobotType.circle: + circle = plt.Circle((x, y), config.robot_radius, color="b") + plt.gcf().gca().add_artist(circle) + out_x, out_y = (np.array([x, y]) + + np.array([np.cos(yaw), np.sin(yaw)]) * config.robot_radius) + plt.plot([x, out_x], [y, out_y], "-k") + From 00358b1d457122debde8980e3c7439df8a0e18b0 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Tue, 2 Jul 2024 09:41:43 +0100 Subject: [PATCH 12/33] Update test_drone_DWA.py --- .../DynamicWindowApproach/test_drone_DWA.py | 27 +------------------ 1 file changed, 1 insertion(+), 26 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/test_drone_DWA.py b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py index 1818a80f8c..3fd5134208 100644 --- a/PathPlanning/DynamicWindowApproach/test_drone_DWA.py +++ b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py @@ -103,34 +103,9 @@ def plot_update(frame, plot_queue, ax, start_position, destinations, fences, con ax.set_ylim(51.68, 51.75) # Set y-axis limits to match the area ax.legend() -def arm_and_takeoff(vehicle, target_altitude): - while not vehicle.is_armable: - print("Waiting for vehicle to initialize...") - time.sleep(1) - - print("Arming motors") - vehicle.mode = VehicleMode("GUIDED") - vehicle.armed = True - - while not vehicle.armed: - print("Waiting for arming...") - time.sleep(1) - - print("Taking off!") - vehicle.simple_takeoff(target_altitude) - - while True: - print(f"Altitude: {vehicle.location.global_relative_frame.alt}") - if vehicle.location.global_relative_frame.alt >= target_altitude * 0.95: - print("Reached target altitude") - break - time.sleep(1) def main(): - arm_and_takeoff(vehicle1, 5) - time.sleep(10) # Wait for some time to ensure vehicle1 has taken off - arm_and_takeoff(vehicle2, 5) - time.sleep(10) # Wait for some time to ensure vehicle2 has taken off + start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for visualization From 16f3e6a800bbcda6d38cc9e552dae3f98cb0bfec Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Tue, 2 Jul 2024 09:42:10 +0100 Subject: [PATCH 13/33] Add files via upload --- .../DynamicWindowApproach/take0ff_arm.py | 70 +++++++++++++++++++ 1 file changed, 70 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/take0ff_arm.py diff --git a/PathPlanning/DynamicWindowApproach/take0ff_arm.py b/PathPlanning/DynamicWindowApproach/take0ff_arm.py new file mode 100644 index 0000000000..7df6ab56ab --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/take0ff_arm.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +""" +© Copyright 2015-2016, 3D Robotics. +guided_set_speed_yaw.py: (Copter Only) +This example shows how to move/direct Copter and send commands in GUIDED mode using DroneKit Python. +Example documentation: http://python.dronekit.io/examples/guided-set-speed-yaw-demo.html +""" +from __future__ import print_function +import numpy as np +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil +import time +import math +import threading +import matplotlib.pyplot as plt +import argparse +from mpl_toolkits.mplot3d import Axes3D + +# Set up option parsing to get connection string +parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') +parser.add_argument('--connect1', help="Vehicle 1 connection target string.") +parser.add_argument('--connect2', help="Vehicle 2 connection target string.") +args = parser.parse_args() + +connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' +connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + +# Connect to the Vehicles +print('Connecting to vehicle on: %s' % connection_string1) +vehicle1 = connect(connection_string1, wait_ready=True) + +print('Connecting to vehicle on: %s' % connection_string2) +vehicle2 = connect(connection_string2, wait_ready=True) + +# Function to arm and takeoff +def arm_and_takeoff(vehicle, aTargetAltitude): + """ + Arms vehicle and fly to aTargetAltitude. + """ + # time.sleep(1) + + print("Arming motors") + vehicle.mode = VehicleMode("GUIDED") + time.sleep(3) + vehicle.armed = True + + + print("Taking off!") + vehicle.simple_takeoff(aTargetAltitude) + # while True: + print(f" Altitude: {vehicle.location.global_relative_frame.alt}") + # if vehicle.location.global_relative_frame.alt >= aTargetAltitude * 0.95: + print("Reached target altitude") + # break + time.sleep(3) + + + +# Arm and take off to altitude of 5 meters for both vehicles +arm_and_takeoff(vehicle1, 5) +time.sleep(10) # Wait for some time to ensure vehicle1 has taken off +arm_and_takeoff(vehicle2, 5) +time.sleep(12) +print("Both vehicles are in the air.") +current_value1 = vehicle1.parameters['WPNAV_SPEED_UP'] +current_value2 = vehicle2.parameters['WPNAV_SPEED_UP'] +print(f"WPNAV_SPEED_UP parameter set to: {current_value1} for vehicle 1") +print(f"WPNAV_SPEED_UP parameter set to: {current_value2} for vehicle 2") + From bd81412dceaf32b1913cab86cd2f7716b517b4d0 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Tue, 2 Jul 2024 09:46:18 +0100 Subject: [PATCH 14/33] Update test_drone_DWA.py --- PathPlanning/DynamicWindowApproach/test_drone_DWA.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/test_drone_DWA.py b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py index 3fd5134208..ab17fb33c3 100644 --- a/PathPlanning/DynamicWindowApproach/test_drone_DWA.py +++ b/PathPlanning/DynamicWindowApproach/test_drone_DWA.py @@ -110,7 +110,7 @@ def main(): start_position = LocationGlobalRelative(51.73, 0.483, 45) # Starting point for visualization destinations = [ - [51.75376, 0.48471, 45], # Springfield Hospital + [51.95376, 0.48471, 45], # Springfield Hospital [51.73112, 0.4711, 56], # Chelmsford & Essex Hospital [51.73602, 0.47358, 33], # Fitzroy Surgery Chelmsford [51.743516, 0.47556, 45], # Priory Hospital Chelmsford From 801a4a5fecc7bdbb61b964d01aea788fb0dd2172 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Tue, 2 Jul 2024 09:56:37 +0100 Subject: [PATCH 15/33] Update take0ff_arm.py --- .../DynamicWindowApproach/take0ff_arm.py | 31 ++++++++++++++++--- 1 file changed, 26 insertions(+), 5 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/take0ff_arm.py b/PathPlanning/DynamicWindowApproach/take0ff_arm.py index 7df6ab56ab..c8a01a8efc 100644 --- a/PathPlanning/DynamicWindowApproach/take0ff_arm.py +++ b/PathPlanning/DynamicWindowApproach/take0ff_arm.py @@ -56,15 +56,36 @@ def arm_and_takeoff(vehicle, aTargetAltitude): time.sleep(3) +# Set WPNAV_SPEED_UP parameter to 1000 + +set_parameter_value(vehicle1, 'WPNAV_SPEED_UP', 1000) + +set_parameter_value(vehicle2, 'WPNAV_SPEED_UP', 1000) + + + +# Wait for the parameter to be set (optional) + +time.sleep(1) + + + +# Example: Reading back the parameter to verify + +current_value1 = vehicle1.parameters['WPNAV_SPEED_UP'] + +current_value2 = vehicle2.parameters['WPNAV_SPEED_UP'] + +print(f"WPNAV_SPEED_UP parameter set to: {current_value1} for vehicle 1") + +print(f"WPNAV_SPEED_UP parameter set to: {current_value2} for vehicle 2") + # Arm and take off to altitude of 5 meters for both vehicles arm_and_takeoff(vehicle1, 5) time.sleep(10) # Wait for some time to ensure vehicle1 has taken off arm_and_takeoff(vehicle2, 5) time.sleep(12) -print("Both vehicles are in the air.") -current_value1 = vehicle1.parameters['WPNAV_SPEED_UP'] -current_value2 = vehicle2.parameters['WPNAV_SPEED_UP'] -print(f"WPNAV_SPEED_UP parameter set to: {current_value1} for vehicle 1") -print(f"WPNAV_SPEED_UP parameter set to: {current_value2} for vehicle 2") + + From 4f23940823dd6d96ee989034f24dc4dbdb7ee49b Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sat, 6 Jul 2024 23:09:04 +0100 Subject: [PATCH 16/33] Add files via upload --- Essex_Hospitals_NoFlyZones.kml | 25876 +++++++++++++++++++++++++++++++ convert_KML_to_TSP.py | 38 + mavproxy_kml.py | 30 + 3 files changed, 25944 insertions(+) create mode 100644 Essex_Hospitals_NoFlyZones.kml create mode 100644 convert_KML_to_TSP.py create mode 100644 mavproxy_kml.py diff --git a/Essex_Hospitals_NoFlyZones.kml b/Essex_Hospitals_NoFlyZones.kml new file mode 100644 index 0000000000..206154702a --- /dev/null +++ b/Essex_Hospitals_NoFlyZones.kml @@ -0,0 +1,25876 @@ + + + + NATS AIM on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.
+ The content of this file is not guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free.]]>
+ + 2024-06-13 + 2024-06-13 + + + + + + + normal + #__managed_style_111482045631BD754BC2 + + + highlight + #__managed_style_284C0E702C31BD754BC2 + + + + + + + + + + + normal + #__managed_style_199B32D61131BD208B69 + + + highlight + #__managed_style_2E7C1EAAA231BD208B69 + + + + + + + + + + normal + #rdpstyle + + + highlight + #highlightStyle + + + + Airspaces + + Danger + + EGD001 TREVOSE HEAD + 501918N 0053042W -
502400N 0053900W -
503200N 0053400W -
503930N 0052400W -
504300N 0051230W -
503830N 0050430W -
501918N 0053042W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552415.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5116666667,50.3216666667,304.8 -5.075,50.6416666667,304.8 -5.2083333333,50.7166666667,304.8 -5.4,50.6583333333,304.8 -5.5666666667,50.5333333333,304.8 -5.65,50.39999999999999,304.8 -5.5116666667,50.3216666667,304.8 + + + + +
+ + EGD003 PLYMOUTH + 501001N 0034740W -
500339N 0033430W -
494105N 0034912W -
493719N 0040938W -
501001N 0034740W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.7944444444,50.16694444440001,6705.599999999999 -4.1605555556,49.6219444444,6705.599999999999 -3.82,49.68472222220001,6705.599999999999 -3.575,50.0608333333,6705.599999999999 -3.7944444444,50.16694444440001,6705.599999999999 + + + + +
+ + EGD004 PLYMOUTH + 500339N 0033430W -
500103N 0032910W -
494653N 0031655W -
494105N 0034912W -
500339N 0033430W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.575,50.0608333333,6705.599999999999 -3.82,49.68472222220001,6705.599999999999 -3.281944444400001,49.7813888889,6705.599999999999 -3.4861111111,50.0175,6705.599999999999 -3.575,50.0608333333,6705.599999999999 + + + + +
+ + EGD005A PREDANNACK + A circle, 3 NM radius, centred at 500007N 0051354W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2317694444,50.0519840728,2438.4 -5.2382609639,50.0518087079,2438.4 -5.244706809,50.0512838469,2438.4 -5.2510616297,50.0504131826,2438.4 -5.2572807223,50.0492028405,2438.4 -5.2633203464,50.04766133530001,2438.4 -5.2691380355,50.04579951060001,2438.4 -5.2746928974,50.0436304617,2438.4 -5.2799459031,50.0411694431,2438.4 -5.2848601634,50.0384337598,2438.4 -5.2894011878,50.03544264570001,2438.4 -5.2935371276,50.0322171262,2438.4 -5.2972389989,50.0287798704,2438.4 -5.3004808854,50.0251550305,2438.4 -5.3032401186,50.0213680712,2438.4 -5.3054974349,50.01744559,2438.4 -5.3072371079,50.0134151297,2438.4 -5.308447056,50.00930498430001,2438.4 -5.3091189239,50.0051440001,2438.4 -5.3092481369,50.0009613725,2438.4 -5.3088339296,49.9967864416,2438.4 -5.3078793473,49.9926484858,2438.4 -5.3063912206,49.98857651649999,2438.4 -5.3043801136,49.98459907579999,2438.4 -5.3018602465,49.9807440358,2438.4 -5.2988493928,49.97703840469999,2438.4 -5.2953687514,49.9735081377,2438.4 -5.2914427962,49.9701779565,2438.4 -5.2870991023,49.9670711763,2438.4 -5.2823681521,49.9642095444,2438.4 -5.2772831207,49.9616130881,2438.4 -5.2718796434,49.9592999758,2438.4 -5.2661955671,49.957286391,2438.4 -5.2602706859,49.95558641960001,2438.4 -5.2541464643,49.9542119522,2438.4 -5.2478657491,49.9531726018,2438.4 -5.2414724716,49.9524756371,2438.4 -5.2350113432,49.95212593200001,2438.4 -5.2285275456,49.95212593200001,2438.4 -5.2220664173,49.9524756371,2438.4 -5.2156731398,49.9531726018,2438.4 -5.2093924246,49.9542119522,2438.4 -5.203268203,49.95558641960001,2438.4 -5.1973433218,49.957286391,2438.4 -5.1916592454,49.9592999758,2438.4 -5.1862557682,49.9616130881,2438.4 -5.1811707367,49.9642095444,2438.4 -5.1764397866,49.9670711763,2438.4 -5.1720960927,49.9701779565,2438.4 -5.1681701375,49.9735081377,2438.4 -5.1646894961,49.97703840469999,2438.4 -5.1616786423,49.9807440358,2438.4 -5.1591587753,49.98459907579999,2438.4 -5.1571476683,49.98857651649999,2438.4 -5.1556595416,49.9926484858,2438.4 -5.1547049593,49.9967864416,2438.4 -5.154290752,50.0009613725,2438.4 -5.154419965,50.0051440001,2438.4 -5.1550918329,50.00930498430001,2438.4 -5.156301781,50.0134151297,2438.4 -5.158041454,50.01744559,2438.4 -5.1602987703,50.0213680712,2438.4 -5.1630580035,50.0251550305,2438.4 -5.16629989,50.0287798704,2438.4 -5.1700017613,50.0322171262,2438.4 -5.1741377011,50.03544264570001,2438.4 -5.1786787255,50.0384337598,2438.4 -5.1835929857,50.0411694431,2438.4 -5.1888459915,50.0436304617,2438.4 -5.1944008533,50.04579951060001,2438.4 -5.2002185425,50.04766133530001,2438.4 -5.2062581666,50.0492028405,2438.4 -5.2124772592,50.0504131826,2438.4 -5.2188320799,50.0512838469,2438.4 -5.225277925,50.0518087079,2438.4 -5.2317694444,50.0519840728,2438.4 + + + + +
+ + EGD005B PREDANNACK CORRIDOR + 500208N 0051722W -
495818N 0052242W -
495124N 0051200W -
495629N 0050728W -
495809N 0051024W thence clockwise by the arc of a circle radius 3 NM centred on 500007N 0051354W to -
500208N 0051722W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2893774722,50.0354596389,2438.4 -5.3783333333,49.97166666670001,2438.4 -5.2,49.8566666667,2438.4 -5.1243299444,49.94131175,2438.4 -5.1732655,49.969289,2438.4 -5.1776868569,49.9662693871,2438.4 -5.1824813042,49.9634969443,2438.4 -5.1876157091,49.96099079620001,2438.4 -5.1930546103,49.9587682276,2438.4 -5.198760463,49.9568445653,2438.4 -5.2046938963,49.9552330729,2438.4 -5.2108139835,49.95394486080001,2438.4 -5.2170785222,49.9529888094,2438.4 -5.2234443235,49.9523715092,2438.4 -5.2298675064,49.95209721499999,2438.4 -5.2363037984,49.95216781749999,2438.4 -5.2427088373,49.9525828301,2438.4 -5.2490384744,49.9533393922,2438.4 -5.2552490759,49.9544322888,2438.4 -5.2612978212,49.9558539861,2438.4 -5.2671429954,49.9575946829,2438.4 -5.2727442751,49.95964237780001,2438.4 -5.2780630047,49.9619829511,2438.4 -5.2830624614,49.9646002613,2438.4 -5.2877081082,49.9674762558,2438.4 -5.2919678313,49.9705910944,2438.4 -5.2958121626,49.9739232851,2438.4 -5.2992144834,49.9774498319,2438.4 -5.3021512098,49.9811463922,2438.4 -5.3046019571,49.9849874443,2438.4 -5.3065496835,49.9889464626,2438.4 -5.3079808099,49.9929961005,2438.4 -5.3088853174,49.9971083784,2438.4 -5.30925682,50.0012548768,2438.4 -5.309092612,50.0054069326,2438.4 -5.3083936908,50.0095358368,2438.4 -5.3071647539,50.013613033,2438.4 -5.3054141696,50.0176103157,2438.4 -5.3031539236,50.0215000252,2438.4 -5.3003995384,50.0252552394,2438.4 -5.2971699697,50.0288499612,2438.4 -5.2934874772,50.0322592989,2438.4 -5.2893774722,50.0354596389,2438.4 + + + + +
+ + EGD006A FALMOUTH BAY + 501244N 0044659W -
500726N 0044228W -
500000N 0045430W -
500924N 0045430W -
501244N 0044659W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7830555556,50.21222222219999,6705.599999999999 -4.9083333333,50.1566666667,6705.599999999999 -4.9083333333,50,6705.599999999999 -4.7077777778,50.1238888889,6705.599999999999 -4.7830555556,50.21222222219999,6705.599999999999 + + + + +
+ + EGD006B FALMOUTH BAY + 495907N 0050506W -
500500N 0045948W -
500924N 0045430W -
500000N 0045430W -
495646N 0045634W -
495907N 0050506W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0849987222,49.9851711667,2438.4 -4.9428074167,49.9462036944,2438.4 -4.9083333333,50,2438.4 -4.9083333333,50.1566666667,2438.4 -4.9966666667,50.0833333333,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + +
+ + EGD006C FALMOUTH BAY + 495907N 0050506W -
495124N 0051200W -
495124N 0050000W -
495646N 0045634W -
495907N 0050506W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0849987222,49.9851711667,2438.4 -5.2,49.8566666667,2438.4 -5,49.8566666667,2438.4 -4.9428074167,49.9462036944,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + +
+ + EGD007A FOWEY + 501801N 0043643W -
501820N 0043152W -
501857N 0042738W -
501550N 0042458W -
500922N 0044407W -
501202N 0044623W -
501801N 0043643W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6119444444,50.3002777778,6705.599999999999 -4.7730555556,50.2005555556,6705.599999999999 -4.7352777778,50.1561111111,6705.599999999999 -4.4161111111,50.26388888890001,6705.599999999999 -4.4605555556,50.31583333330001,6705.599999999999 -4.5311111111,50.30555555560001,6705.599999999999 -4.6119444444,50.3002777778,6705.599999999999 + + + + +
+ + EGD007B FOWEY + 501550N 0042458W -
501342N 0042309W -
500726N 0044228W -
500922N 0044407W -
501550N 0042458W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4161111111,50.26388888890001,6705.599999999999 -4.7352777778,50.1561111111,6705.599999999999 -4.7077777778,50.1238888889,6705.599999999999 -4.3858333333,50.2283333333,6705.599999999999 -4.4161111111,50.26388888890001,6705.599999999999 + + + + +
+ + EGD007C FOWEY INNER + 501733N 0044334W -
501801N 0043643W -
501202N 0044623W -
501244N 0044659W -
501414N 0044441W -
501647N 0044447W -
501733N 0044334W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards..

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7261111111,50.2925,609.6 -4.7463888889,50.27972222219999,609.6 -4.7447222222,50.23722222220001,609.6 -4.7830555556,50.21222222219999,609.6 -4.7730555556,50.2005555556,609.6 -4.6119444444,50.3002777778,609.6 -4.7261111111,50.2925,609.6 + + + + +
+ + EGD008A PLYMOUTH + 495654N 0045629W -
493715N 0041003W -
492745N 0050000W -
495124N 0050000W -
495654N 0045629W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9413888889,49.94833333330001,6705.599999999999 -5,49.8566666667,6705.599999999999 -5,49.4625,6705.599999999999 -4.1675,49.6208333333,6705.599999999999 -4.9413888889,49.94833333330001,6705.599999999999 + + + + +
+ + EGD008B PLYMOUTH + 494740N 0043430W -
494438N 0040446W -
493719N 0040938W -
493715N 0041003W -
494740N 0043430W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.575,49.79444444440001,6705.599999999999 -4.1675,49.6208333333,6705.599999999999 -4.1605555556,49.6219444444,6705.599999999999 -4.0794444444,49.7438888889,6705.599999999999 -4.575,49.79444444440001,6705.599999999999 + + + + +
+ + EGD008C PLYMOUTH + 501140N 0042931W thence anti-clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to
500623N 0035008W -
494438N 0040446W -
494740N 0043430W -
495654N 0045629W -
500000N 0045430W -
500726N 0044228W -
501140N 0042931W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4919444444,50.1944444444,16764 -4.7077777778,50.1238888889,16764 -4.9083333333,50,16764 -4.9413888889,49.94833333330001,16764 -4.575,49.79444444440001,16764 -4.0794444444,49.7438888889,16764 -3.8355555556,50.1063888889,16764 -3.8477298237,50.10032261750001,16764 -3.8600996985,50.094429589,16764 -3.8727887629,50.08882582250001,16764 -3.8857806495,50.0835184994,16764 -3.8990586201,50.0785144188,16764 -3.9126055863,50.0738199893,16764 -3.926404131,50.0694412212,16764 -3.9404365295,50.06538371910001,16764 -3.9546847725,50.061652675,16764 -3.9691305873,50.058252862,16764 -3.9837554609,50.0551886287,16764 -3.9985406625,50.05246389340001,16764 -4.0134672665,50.05008214,16764 -4.0285161756,50.0480464131,16764 -4.0436681441,50.0463593148,16764 -4.0589038012,50.0450230012,16764 -4.0742036748,50.04403918,16764 -4.0895482148,50.0434091085,16764 -4.104917817,50.0431335916,16764 -4.120292847,50.0432129814,16764 -4.1356536637,50.0436471765,16764 -4.1509806431,50.0444356221,16764 -4.1662542024,50.04557731069999,16764 -4.1814548235,50.0470707833,16764 -4.1965630767,50.04891413150001,16764 -4.2115596442,50.0511049992,16764 -4.2264253437,50.05364058589999,16764 -4.241141152,50.05651765,16764 -4.2556882278,50.05973251270001,16764 -4.2700479348,50.0632810627,16764 -4.2842018648,50.0671587608,16764 -4.2981318601,50.0713606457,16764 -4.311820036,50.07588133990001,16764 -4.3252488027,50.0807150566,16764 -4.3384008876,50.0858556064,16764 -4.3512593561,50.09129640490001,16764 -4.3638076335,50.097030481,16764 -4.3760295253,50.1030504853,16764 -4.387909238,50.109348699,16764 -4.3994313989,50.11591704389999,16764 -4.4105810759,50.1227470915,16764 -4.4213437965,50.12983007439999,16764 -4.4317055664,50.1371568961,16764 -4.4416528883,50.1447181433,16764 -4.4511727785,50.1525040966,16764 -4.4602527853,50.1605047435,16764 -4.4688810044,50.1687097899,16764 -4.4770460956,50.1771086739,16764 -4.484737298,50.1856905783,16764 -4.4919444444,50.1944444444,16764 + + + + +
+ + EGD009A WEMBURY + 501904N 0040633W -
501001N 0034740W -
500623N 0035008W thence clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to
501140N 0042931W -
501904N 0040633W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC – Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1091666667,50.3177777778,16764 -4.4919444444,50.1944444444,16764 -4.4849292755,50.1856225616,16764 -4.477234108,50.1770362709,16764 -4.4690648117,50.1686330948,16764 -4.460432153,50.160423856,16764 -4.4513474783,50.152419122,16764 -4.4418226976,50.1446291917,16764 -4.4318702695,50.1370640831,16764 -4.421503184,50.1297335201,16764 -4.4107349457,50.1226469211,16764 -4.3995795559,50.1158133869,16764 -4.3880514944,50.1092416896,16764 -4.376165701,50.1029402616,16764 -4.3639375563,50.0969171856,16764 -4.3513828619,50.0911801839,16764 -4.3385178203,50.08573660980001,16764 -4.3253590148,50.0805934379,16764 -4.3119233883,50.0757572558,16764 -4.2982282225,50.071234256,16764 -4.2842911159,50.06703022840001,16764 -4.2701299621,50.0631505531,16764 -4.2557629282,50.0596001938,16764 -4.2412084315,50.056383692,16764 -4.2264851176,50.0535051612,16764 -4.2116118373,50.0509682819,16764 -4.1966076236,50.0487762975,16764 -4.1814916682,50.0469320097,16764 -4.1662832985,50.04543777580001,16764 -4.1510019541,50.0442955053,16764 -4.1356671629,50.0435066578,16764 -4.1202985175,50.0430722415,16764 -4.1049156516,50.0429928112,16764 -4.0895382162,50.0432684685,16764 -4.0741858556,50.0438988612,16764 -4.0588781838,50.0448831838,16764 -4.0436347606,50.04622017849999,16764 -4.0284750679,50.0479081368,16764 -4.0134184863,50.04994490129999,16764 -3.9984842711,50.0523278689,16764 -3.9836915291,50.05505399319999,16764 -3.9690591956,50.0581197887,16764 -3.9546060106,50.06152133509999,16764 -3.940350496599999,50.0652542816,16764 -3.9263109353,50.0693138528,16764 -3.9125053453,50.0736948539,16764 -3.898951460000001,50.07839167760001,16764 -3.8856667055,50.0833983106,16764 -3.8726681787,50.0887083411,16764 -3.8599726265,50.0943149665,16764 -3.8475964243,50.1002110019,16764 -3.8355555556,50.1063888889,16764 -3.7944444444,50.16694444440001,16764 -4.1091666667,50.3177777778,16764 + + + + +
+ + EGD009B WEMBURY + 501342N 0042309W -
501951N 0041015W thence clockwise by the arc of a circle radius 2.5 NM centred on 501904N 0040633W to
501735N 0040325W -
501904N 0040633W -
501342N 0042309W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC – Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Plymouth Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3858333333,50.2283333333,6705.599999999999 -4.1091666667,50.3177777778,6705.599999999999 -4.0569444444,50.29305555560001,6705.599999999999 -4.0536641121,50.2962012969,6705.599999999999 -4.0508306672,50.2995200299,6705.599999999999 -4.0484794125,50.3029899108,6705.599999999999 -4.0466298918,50.30658225509999,6705.599999999999 -4.0452975128,50.3102673594,6705.599999999999 -4.0444934154,50.31401474640001,6705.599999999999 -4.0442243764,50.3177934166,6705.599999999999 -4.0444927492,50.3215721043,6705.599999999999 -4.0452964397,50.32531953660001,6705.599999999999 -4.0466289201,50.32900469150001,6705.599999999999 -4.0484792784,50.3325970559,6705.599999999999 -4.050832305,50.33606687810001,6705.599999999999 -4.0536686156,50.339385415,6705.599999999999 -4.0569648077,50.3425251708,6705.599999999999 -4.0606936531,50.3454601258,6705.599999999999 -4.0648243209,50.34816595309999,6705.599999999999 -4.0693226319,50.3506202208,6705.599999999999 -4.0741513417,50.3528025791,6705.599999999999 -4.0792704488,50.3546949305,6705.599999999999 -4.0846375278,50.35628158019999,6705.599999999999 -4.0902080822,50.3575493674,6705.599999999999 -4.0959359153,50.3584877753,6705.599999999999 -4.1017735161,50.3590890188,6705.599999999999 -4.1076724557,50.3593481099,6705.599999999999 -4.1135837926,50.3592628989,6705.599999999999 -4.1194584815,50.3588340927,6705.599999999999 -4.1252477834,50.3580652491,6705.599999999999 -4.1309036735,50.3569627465,6705.599999999999 -4.136379242,50.3555357309,6705.599999999999 -4.1416290858,50.35379603959999,6705.599999999999 -4.1466096878,50.351758102,6705.599999999999 -4.1512797789,50.3494388193,6705.599999999999 -4.1556006814,50.3468574234,6705.599999999999 -4.1595366302,50.3440353162,6705.599999999999 -4.163055069,50.3409958917,6705.599999999999 -4.1661269193,50.3377643405,6705.599999999999 -4.1687268196,50.3343674403,6705.599999999999 -4.1708333333,50.3308333333,6705.599999999999 -4.3858333333,50.2283333333,6705.599999999999 + + + + +
+ + EGD011A OKEHAMPTON + 504226N 0040146W -
504311N 0035854W -
503937N 0035613W -
503725N 0035712W -
503744N 0035801W -
503729N 0040101W -
504019N 0040341W -
504226N 0040146W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 10000 FT ALT.

Vertical Limits: Normally 10000 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1980/949. UAS BVLOS will not be conducted above 10000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0294444444,50.7072222222,7345.68 -4.0613888889,50.6719444444,7345.68 -4.0169444444,50.6247222222,7345.68 -3.9669444444,50.62888888890001,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9369444444,50.6602777778,7345.68 -3.9816666667,50.7197222222,7345.68 -4.0294444444,50.7072222222,7345.68 + + + + +
+ + EGD011B WILLSWORTHY + 504019N 0040341W -
503729N 0040101W -
503726N 0040136W -
503550N 0040444W -
503747N 0040558W -
504019N 0040341W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 4500 FT ALT.

Vertical Limits: Normally 4500 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1980/950. UAS BVLOS will not be conducted above 4500 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0613888889,50.6719444444,7345.68 -4.0994444444,50.6297222222,7345.68 -4.0788888889,50.5972222222,7345.68 -4.0266666667,50.62388888890001,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0613888889,50.6719444444,7345.68 + + + + +
+ + EGD011C MERRIVALE + 503726N 0040136W -
503729N 0040101W -
503744N 0035801W -
503725N 0035712W -
503426N 0035832W -
503402N 0040336W -
503550N 0040444W -
503726N 0040136W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 10000 FT ALT.

Vertical Limits: Normally 10000 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1979/1721. UAS BVLOS will not be conducted above 10000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0266666667,50.62388888890001,7345.68 -4.0788888889,50.5972222222,7345.68 -4.06,50.5672222222,7345.68 -3.9755555556,50.57388888890001,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9669444444,50.62888888890001,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0266666667,50.62388888890001,7345.68 + + + + +
+ + EGD012 LYME BAY NORTH + 504220N 0024500W -
503400N 0024500W following the line of latitude to -
503400N 0030500W -
503000N 0031730W -
503650N 0031500W -
504106N 0030544W - then along the coastline to -
504220N 0024500W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.7055555556,5486.400000000001 -2.7539289167,50.70698188890001,5486.400000000001 -2.7687341389,50.71156202780001,5486.400000000001 -2.7852465278,50.7163986111,5486.400000000001 -2.7919162222,50.717073,5486.400000000001 -2.7971543056,50.7168574444,5486.400000000001 -2.8015669444,50.7180863333,5486.400000000001 -2.8077796667,50.71687425,5486.400000000001 -2.8110547222,50.7178408333,5486.400000000001 -2.8169062778,50.7203182778,5486.400000000001 -2.8306950556,50.72291902780001,5486.400000000001 -2.8383291111,50.7219649722,5486.400000000001 -2.8451533056,50.7232648056,5486.400000000001 -2.8632228333,50.7273595556,5486.400000000001 -2.8797339722,50.7303860278,5486.400000000001 -2.896757083299999,50.73223300000001,5486.400000000001 -2.9061245,50.73297002779999,5486.400000000001 -2.9145946944,50.73128499999999,5486.400000000001 -2.9238843611,50.7280638889,5486.400000000001 -2.9262131111,50.72399813890001,5486.400000000001 -2.9284638056,50.72317077780001,5486.400000000001 -2.9318530833,50.7226041111,5486.400000000001 -2.934091083299999,50.72114716669999,5486.400000000001 -2.9342041389,50.7197072222,5486.400000000001 -2.9360313333,50.7189730556,5486.400000000001 -2.9438005278,50.71783113890001,5486.400000000001 -2.9500746944,50.7128335,5486.400000000001 -2.9523317222,50.7123653889,5486.400000000001 -2.9613887778,50.71193130559999,5486.400000000001 -2.962810611100001,50.7121893889,5486.400000000001 -2.96587475,50.7096457222,5486.400000000001 -2.9731907222,50.70724644439999,5486.400000000001 -2.9783781111,50.7046847222,5486.400000000001 -2.9843237222,50.7045447222,5486.400000000001 -2.9877430833,50.7055051389,5486.400000000001 -2.9900088333,50.7054859167,5486.400000000001 -2.9936640833,50.7041956667,5486.400000000001 -2.9989896667,50.7015418889,5486.400000000001 -3.0043338611,50.6997871111,5486.400000000001 -3.0073015,50.6994916667,5486.400000000001 -3.0135101667,50.6984485278,5486.400000000001 -3.0194490278,50.6980369722,5486.400000000001 -3.0249826389,50.6985280833,5486.400000000001 -3.027548888900001,50.6993149722,5486.400000000001 -3.0350669722,50.6998780278,5486.400000000001 -3.0450162778,50.7014981389,5486.400000000001 -3.0491265556,50.7016410833,5486.400000000001 -3.0536555833,50.7015103056,5486.400000000001 -3.0611743056,50.7020716944,5486.400000000001 -3.0658449167,50.7019391389,5486.400000000001 -3.07263125,50.70142719439999,5486.400000000001 -3.074894694400001,50.7013163889,5486.400000000001 -3.077708,50.7004809444,5486.400000000001 -3.0799693056,50.7002801389,5486.400000000001 -3.0816249444,50.6983760556,5486.400000000001 -3.0843944167,50.6956520833,5486.400000000001 -3.0882003056,50.6948971111,5486.400000000001 -3.0891350833,50.6924599722,5486.400000000001 -3.0890976111,50.6908413889,5486.400000000001 -3.0911355,50.68713474999999,5486.400000000001 -3.0919200833,50.68433925,5486.400000000001 -3.0950402778,50.68457980559999,5486.400000000001 -3.095555555599999,50.685,5486.400000000001 -3.25,50.6138888889,5486.400000000001 -3.2916666667,50.5,5486.400000000001 -3.0833333333,50.56666666669999,5486.400000000001 -2.972222222200001,50.56666666669999,5486.400000000001 -2.8611111111,50.56666666669999,5486.400000000001 -2.75,50.56666666669999,5486.400000000001 -2.75,50.7055555556,5486.400000000001 + + + + +
+ + EGD013 LYME BAY + 503400N 0024500W -
500200N 0024500W -
500200N 0025800W -
500800N 0030430W -
502500N 0031730W -
503000N 0031730W -
503400N 0030500W -
503400N 0024500W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.56666666669999,16764 -3.0833333333,50.56666666669999,16764 -3.2916666667,50.5,16764 -3.2916666667,50.4166666667,16764 -3.075000000000001,50.13333333329999,16764 -2.9666666667,50.0333333333,16764 -2.75,50.0333333333,16764 -2.75,50.56666666669999,16764 + + + + +
+ + EGD014 PORTLAND + 503818N 0023424W -
503736N 0023230W -
503530N 0022948W -
503400N 0023124W -
503400N 0023000W -
502931N 0023000W -
503400N 0024500W -
503400N 0024200W -
503700N 0024130W -
503818N 0023424W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 5000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 15000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5733333333,50.6383333333,4572 -2.6916666667,50.6166666667,4572 -2.7,50.56666666669999,4572 -2.75,50.56666666669999,4572 -2.5,50.4919444444,4572 -2.5,50.56666666669999,4572 -2.5233333333,50.56666666669999,4572 -2.4966666667,50.5916666667,4572 -2.5416666667,50.6266666667,4572 -2.5733333333,50.6383333333,4572 + + + + +
+ + EGD015 BOVINGTON + A circle, 500 M radius, centred at 504324N 0021424W
Upper limit: 3600 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01929-403765.

Remarks: SI 1936/118.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.24,50.7278279975,1097.28 -2.2419105304,50.7276613075,1097.28 -2.2436793273,50.7271736038,1097.28 -2.2451751801,50.726401066,1097.28 -2.24628714,50.7254010021,1097.28 -2.2469327516,50.724247594,1097.28 -2.2470641634,50.72302639250001,1097.28 -2.2466716685,50.7218279703,1097.28 -2.2457844129,50.7207412039,1097.28 -2.2444682231,50.7198466836,1097.28 -2.2428207176,50.7192107394,1097.28 -2.240964066,50.7188805253,1097.28 -2.239035934,50.7188805253,1097.28 -2.2371792824,50.7192107394,1097.28 -2.2355317769,50.7198466836,1097.28 -2.2342155871,50.7207412039,1097.28 -2.2333283315,50.7218279703,1097.28 -2.2329358366,50.72302639250001,1097.28 -2.2330672484,50.724247594,1097.28 -2.23371286,50.7254010021,1097.28 -2.2348248199,50.726401066,1097.28 -2.2363206727,50.7271736038,1097.28 -2.2380894696,50.7276613075,1097.28 -2.24,50.7278279975,1097.28 + + + + +
+ + EGD017 PORTLAND + 503400N 0024500W -
502931N 0023000W -
500200N 0023000W -
500200N 0024500W -
503400N 0024500W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.56666666669999,16764 -2.75,50.0333333333,16764 -2.5,50.0333333333,16764 -2.5,50.4919444444,16764 -2.75,50.56666666669999,16764 + + + + +
+ + EGD021 PORTLAND + 503500N 0022000W -
503500N 0021614W -
503154N 0021624W -
503000N 0021700W -
502918N 0021718W -
502500N 0021500W -
502931N 0023000W -
503000N 0023000W -
503000N 0022000W -
503500N 0022000W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3333333333,50.5833333333,4572 -2.3333333333,50.5,4572 -2.5,50.5,4572 -2.5,50.4919444444,4572 -2.25,50.4166666667,4572 -2.2883333333,50.48833333329999,4572 -2.2833333333,50.5,4572 -2.2733333333,50.5316666667,4572 -2.2705555556,50.5833333333,4572 -2.3333333333,50.5833333333,4572 + + + + +
+ + EGD023 PORTLAND + 502931N 0023000W -
502500N 0021500W -
500200N 0021500W -
500200N 0023000W -
502931N 0023000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5,50.4919444444,16764 -2.5,50.0333333333,16764 -2.25,50.0333333333,16764 -2.25,50.4166666667,16764 -2.5,50.4919444444,16764 + + + + +
+ + EGD026 LULWORTH + 504020N 0020755W -
503950N 0020732W -
503751N 0020753W -
503644N 0020813W -
503503N 0020440W -
503030N 0020043W -
502654N 0020230W -
502500N 0020842W -
502500N 0021500W -
502918N 0021718W -
503000N 0021700W -
503154N 0021624W -
503536N 0021612W -
503700N 0021447W -
503800N 0021430W -
503825N 0021137W -
504028N 0021137W -
504020N 0020755W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: Vertical Limits: OCNL notified to ALT 20000.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS less than 150 KTS).

Service: SUACS not available during notified operating hours.

SUAAIS: Plymouth Military on 124.150 MHz when open, London Information on 124.750 MHz thereafter.

Contact: Booking: FOST Eastern Area Manager, Tel: 01752-557752 for the week before, FOST Duty Operations for the current week. Range Information on 01929-404859 or 01929-404712.

Remarks: SI 1978/1663. Unmanned Aircraft Systems (VLOS/BVLOS
less than 150 KTS) will not be conducted above FL 115 and north of a line
503813N 0021301W, 503746N 0021005W and 503810N 0020750W.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1319444444,50.6722222222,4572 -2.1936111111,50.6744444444,4572 -2.1936111111,50.6402777778,4572 -2.2416666667,50.6333333333,4572 -2.2463888889,50.6166666667,4572 -2.27,50.5933333333,4572 -2.2733333333,50.5316666667,4572 -2.2833333333,50.5,4572 -2.2883333333,50.48833333329999,4572 -2.25,50.4166666667,4572 -2.145,50.4166666667,4572 -2.0416666667,50.4483333333,4572 -2.0119444444,50.50833333330001,4572 -2.0777777778,50.5841666667,4572 -2.1369444444,50.6122222222,4572 -2.1313888889,50.6308333333,4572 -2.1255555556,50.6638888889,4572 -2.1319444444,50.6722222222,4572 + + + + +
+ + EGD031 PORTLAND + 503626N 0015635W -
503000N 0015635W -
503000N 0020058W -
503030N 0020043W -
503412N 0020356W -
503435N 0020320W - then along the coastline in an easterly direction to -
503626N 0015635W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9430555556,50.6072222222,4572 -1.9470027778,50.60444999999999,4572 -1.9484166667,50.6030111111,4572 -1.9506833333,50.5973472222,4572 -1.9489916667,50.5944666667,4572 -1.9540805556,50.59213055560001,4572 -1.9552111111,50.5911416667,4572 -1.9583222222,50.5903333333,4572 -1.9653861111,50.59078611110001,4572 -1.9679277778,50.5904277778,4572 -1.9701888889,50.59078611110001,4572 -1.9738611111,50.5901583333,4572 -1.9772527778,50.5899805556,4572 -1.9812083333,50.5894416667,4572 -1.9857305556,50.5900694444,4572 -1.9877083333,50.5896222222,4572 -1.9964666667,50.59034166670001,4572 -2.0029666667,50.5899805556,4572 -2.0086194444,50.5895305556,4572 -2.014975,50.5888111111,4572 -2.0185083333,50.5880916667,4572 -2.0244416667,50.5871916667,4572 -2.0279722222,50.5851222222,4572 -2.0306527778,50.5829611111,4572 -2.0361611111,50.57981388889999,4572 -2.0394083333,50.5784638889,4572 -2.0427972222,50.5772027778,4572 -2.0454805556,50.5765722222,4572 -2.049575,50.5761194444,4572 -2.0524,50.5754,4572 -2.0555555556,50.5763888889,4572 -2.0655555556,50.57,4572 -2.0119444444,50.50833333330001,4572 -2.0161111111,50.5,4572 -1.9430555556,50.5,4572 -1.9430555556,50.6072222222,4572 + + + + +
+ + EGD036 PORTSMOUTH + 502927N 0011208W -
500000N 0011126W -
500000N 0014301W -
500620N 0014207W -
502927N 0011208W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate or through Southampton or Jersey ATSUs, as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2022222222,50.4908333333,16764 -1.7019444444,50.10555555559999,16764 -1.7169444444,50,16764 -1.1905555556,50,16764 -1.2022222222,50.4908333333,16764 + + + + +
+ + EGD037 PORTSMOUTH + 503700N 0010211W -
503700N 0003938W -
503000N 0003213W -
503000N 0011124W -
503700N 0010211W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0363888889,50.6166666667,16764 -1.19,50.5,16764 -0.5369444444,50.5,16764 -0.6605555556,50.6166666667,16764 -1.0363888889,50.6166666667,16764 + + + + +
+ + EGD038 PORTSMOUTH + 503000N 0011124W -
503000N 0005000W -
500000N 0005000W -
500000N 0011126W -
502927N 0011208W -
503000N 0011124W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.19,50.5,16764 -1.2022222222,50.4908333333,16764 -1.1905555556,50,16764 -0.8333333333000001,50,16764 -0.8333333333000001,50.5,16764 -1.19,50.5,16764 + + + + +
+ + EGD039 PORTSMOUTH + 503000N 0005000W -
503000N 0003213W -
502948N 0003200W -
500000N 0003200W -
500000N 0005000W -
503000N 0005000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8333333333000001,50.5,16764 -0.8333333333000001,50,16764 -0.5333333333,50,16764 -0.5333333333,50.4966666667,16764 -0.5369444444,50.5,16764 -0.8333333333000001,50.5,16764 + + + + +
+ + EGD040 PORTSMOUTH + 502948N 0003200W -
501347N 0001511W -
500000N 0003155W -
500000N 0003200W -
502948N 0003200W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5333333333,50.4966666667,16764 -0.5333333333,50,16764 -0.5319444444,50,16764 -0.2530555556,50.2297222222,16764 -0.5333333333,50.4966666667,16764 + + + + +
+ + EGD044 LYDD RANGES + 505525N 0005534E -
505328N 0005613E -
505238N 0005359E -
505237N 0005015E -
505420N 0004748E -
505554N 0005009E -
505650N 0005348E -
505525N 0005534E
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225503.

Remarks: SI 1988/1465.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9261111111,50.9236111111,1219.2 0.8966666666999998,50.94722222219999,1219.2 0.8358333333,50.9316666667,1219.2 0.7966666667,50.9055555556,1219.2 0.8375000000000001,50.8769444444,1219.2 0.8997222221999999,50.8772222222,1219.2 0.9369444444,50.8911111111,1219.2 0.9261111111,50.9236111111,1219.2 + + + + +
+ + EGD061 WOODBURY COMMON + A circle, 926 M radius, centred at 504049N 0032051W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Exeter APP on 128.980 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01395-272972.

Remarks: SI 2009/3284.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3475,50.6886019548,457.2 -3.3501377665,50.68843152869999,457.2 -3.3526674871,50.6879272312,457.2 -3.3549855484,50.68710971849999,457.2 -3.3569970187,50.6860124748,457.2 -3.3586195398,50.684680439,457.2 -3.3597866995,50.68316816200001,457.2 -3.3604507489,50.6815375708,457.2 -3.3605845512,50.6798554304,457.2 -3.3601826846,50.6781906099,457.2 -3.3592616556,50.6766112617,457.2 -3.3578592141,50.675182033,457.2 -3.356032801,50.6739614205,457.2 -3.3538571928,50.6729993786,457.2 -3.3514214394,50.6723352766,457.2 -3.348825222,50.67199629,457.2 -3.346174778,50.67199629,457.2 -3.3435785606,50.6723352766,457.2 -3.3411428072,50.6729993786,457.2 -3.338967198999999,50.6739614205,457.2 -3.3371407859,50.675182033,457.2 -3.3357383444,50.6766112617,457.2 -3.3348173154,50.6781906099,457.2 -3.334415448800001,50.6798554304,457.2 -3.3345492511,50.6815375708,457.2 -3.3352133005,50.68316816200001,457.2 -3.3363804602,50.684680439,457.2 -3.3380029813,50.6860124748,457.2 -3.3400144516,50.68710971849999,457.2 -3.3423325129,50.6879272312,457.2 -3.3448622335,50.68843152869999,457.2 -3.3475,50.6886019548,457.2 + + + + +
+ + EGD064A SOUTH WEST COMPLEX + 512016N 0071115W -
511616N 0061643W -
502838N 0060046W -
501752N 0070521W -
502621N 0073603W -
503808N 0074914W -
504705N 0075207W -
505745N 0075205W -
512016N 0071115W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8686888889,50.78467222219999,20116.8 -7.820425,50.6354777778,20116.8 -7.6007361111,50.4391444444,20116.8 -7.0891277778,50.2977472222,20116.8 -6.0128138889,50.4771666667,20116.8 -6.278702777800001,51.2711527778,20116.8 -7.1874361111,51.3376777778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,1524 -7.8681916667,50.9625111111,1524 -7.8686888889,50.78467222219999,1524 -7.820425,50.6354777778,1524 -7.6007361111,50.4391444444,1524 -7.0891277778,50.2977472222,1524 -6.0128138889,50.4771666667,1524 -6.278702777800001,51.2711527778,1524 -7.1874361111,51.3376777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,1524 -7.8681916667,50.9625111111,1524 -7.8681916667,50.9625111111,20116.8 -7.1874361111,51.3376777778,20116.8 -7.1874361111,51.3376777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.8681916667,50.9625111111,1524 -7.8686888889,50.78467222219999,1524 -7.8686888889,50.78467222219999,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8681916667,50.9625111111,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.8686888889,50.78467222219999,1524 -7.820425,50.6354777778,1524 -7.820425,50.6354777778,20116.8 -7.8686888889,50.78467222219999,20116.8 -7.8686888889,50.78467222219999,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.820425,50.6354777778,1524 -7.6007361111,50.4391444444,1524 -7.6007361111,50.4391444444,20116.8 -7.820425,50.6354777778,20116.8 -7.820425,50.6354777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.6007361111,50.4391444444,1524 -7.0891277778,50.2977472222,1524 -7.0891277778,50.2977472222,20116.8 -7.6007361111,50.4391444444,20116.8 -7.6007361111,50.4391444444,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.0891277778,50.2977472222,1524 -6.0128138889,50.4771666667,1524 -6.0128138889,50.4771666667,20116.8 -7.0891277778,50.2977472222,20116.8 -7.0891277778,50.2977472222,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.0128138889,50.4771666667,1524 -6.278702777800001,51.2711527778,1524 -6.278702777800001,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -7.1874361111,51.3376777778,1524 -7.1874361111,51.3376777778,20116.8 -6.278702777800001,51.2711527778,20116.8 -6.278702777800001,51.2711527778,1524 + + + + + +
+ + EGD064B SOUTH WEST COMPLEX + 511616N 0061643W -
511207N 0052532W -
510624N 0052510W -
503012N 0054335W -
502838N 0060046W -
511616N 0061643W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.20208055559999,20116.8 -6.278702777800001,51.2711527778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -6.0128138889,50.4771666667,1524 -5.7262777778,50.5032416667,1524 -5.4195055556,51.1065583333,1524 -5.4255305556,51.20208055559999,1524 -6.278702777800001,51.2711527778,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -6.0128138889,50.4771666667,1524 -6.0128138889,50.4771666667,20116.8 -6.278702777800001,51.2711527778,20116.8 -6.278702777800001,51.2711527778,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.0128138889,50.4771666667,1524 -5.7262777778,50.5032416667,1524 -5.7262777778,50.5032416667,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7262777778,50.5032416667,1524 -5.4195055556,51.1065583333,1524 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4195055556,51.1065583333,1524 -5.4255305556,51.20208055559999,1524 -5.4255305556,51.20208055559999,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -6.278702777800001,51.2711527778,1524 -6.278702777800001,51.2711527778,20116.8 -5.4255305556,51.20208055559999,20116.8 -5.4255305556,51.20208055559999,1524 + + + + + +
+ + EGD064C SOUTH WEST COMPLEX + 511207N 0052532W -
511028N 0050621W -
505443N 0043352W -
504712N 0043327W -
504423N 0043914W -
504328N 0043921W -
503012N 0054335W -
510624N 0052510W -
511207N 0052532W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,20116.8 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6538055556,50.7396694444,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5643666667,50.9120277778,20116.8 -5.1057833333,51.1745361111,20116.8 -5.4255305556,51.20208055559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -5.4195055556,51.1065583333,1524 -5.7262777778,50.5032416667,1524 -4.6557722222,50.7243333333,1524 -4.6538055556,50.7396694444,1524 -4.5574972222,50.7866166667,1524 -4.5643666667,50.9120277778,1524 -5.1057833333,51.1745361111,1524 -5.4255305556,51.20208055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -5.4195055556,51.1065583333,1524 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.20208055559999,20116.8 -5.4255305556,51.20208055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4195055556,51.1065583333,1524 -5.7262777778,50.5032416667,1524 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7262777778,50.5032416667,1524 -4.6557722222,50.7243333333,1524 -4.6557722222,50.7243333333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.6557722222,50.7243333333,1524 -4.6538055556,50.7396694444,1524 -4.6538055556,50.7396694444,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6557722222,50.7243333333,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.6538055556,50.7396694444,1524 -4.5574972222,50.7866166667,1524 -4.5574972222,50.7866166667,20116.8 -4.6538055556,50.7396694444,20116.8 -4.6538055556,50.7396694444,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.5574972222,50.7866166667,1524 -4.5643666667,50.9120277778,1524 -4.5643666667,50.9120277778,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5574972222,50.7866166667,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.5643666667,50.9120277778,1524 -5.1057833333,51.1745361111,1524 -5.1057833333,51.1745361111,20116.8 -4.5643666667,50.9120277778,20116.8 -4.5643666667,50.9120277778,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.1057833333,51.1745361111,1524 -5.4255305556,51.20208055559999,1524 -5.4255305556,51.20208055559999,20116.8 -5.1057833333,51.1745361111,20116.8 -5.1057833333,51.1745361111,1524 + + + + + +
+ + EGD110 BRAUNTON BURROWS + 510602N 0041529W -
510606N 0041203W -
510500N 0041200W -
510458N 0041315W -
510516N 0041344W -
510514N 0041527W -
510602N 0041529W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 07870-377646 or 01395-277891.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.2580305556,51.1005694444,609.6 -4.2573722222,51.0870916667,609.6 -4.2288388889,51.0876416667,609.6 -4.2207555556,51.0828472222,609.6 -4.2000694444,51.08323888889999,609.6 -4.2009444444,51.10166111110001,609.6 -4.2580305556,51.1005694444,609.6 + + + + +
+ + EGD113A CASTLEMARTIN + 513937N 0051830W following the line of latitude to -
513937N 0050443W -
513906N 0050320W -
513130N 0050530W -
512900N 0050330W following the line of latitude to -
512900N 0045432W -
512430N 0050220W thence clockwise by the arc of a circle radius 18.1 NM centred on 514213N 0045647W to
513610N 0052408W -
513937N 0051830W
Upper limit: 40000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.

Remarks: SI 1986/1834.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3083333333,51.6602777778,12192 -5.4022222222,51.6027777778,12192 -5.3963665818,51.5933780264,12192 -5.3901403276,51.5840734082,12192 -5.3834198158,51.5749035623,12192 -5.3762128249,51.5658786995,12192 -5.3685276609,51.5570088636,12192 -5.3603731468,51.5483039199,12192 -5.351758612,51.53977354500001,12192 -5.342693881,51.53142721590001,12192 -5.3331892616,51.5232742004,12192 -5.3232555331,51.5153235465,12192 -5.3129039336,51.5075840732,12192 -5.3021461467,51.5000643609,12192 -5.2909942889,51.4927727422,12192 -5.2794608951,51.4857172931,12192 -5.2675589047,51.4789058244,12192 -5.2553016477,51.4723458735,12192 -5.2427028289,51.4660446964,12192 -5.2297765136,51.4600092598,12192 -5.216537112,51.454246234,12192 -5.2029993633,51.448761986,12192 -5.1891783197,51.4435625724,12192 -5.1750893305,51.4386537333,12192 -5.1607480254,51.4340408864,12192 -5.1461702976,51.42972912110001,12192 -5.1313722874,51.4257231931,12192 -5.1163703645,51.4220275198,12192 -5.1011811112,51.4186461753,12192 -5.0858213045,51.4155828866,12192 -5.070307899,51.4128410291,12192 -5.0546580086,51.4104236237,12192 -5.0388888889,51.40833333329999,12192 -4.9088888889,51.48333333330001,12192 -4.9836111111,51.48333333330001,12192 -5.0583333333,51.48333333330001,12192 -5.0916666667,51.525,12192 -5.0555555556,51.6516666667,12192 -5.0786111111,51.6602777778,12192 -5.1934722222,51.6602777778,12192 -5.3083333333,51.6602777778,12192 + + + + +
+ + EGD113B CASTLEMARTIN + 513906N 0050320W thence clockwise by the arc of a circle radius 6.6 NM centred on 513230N 0050400W to
513618N 0045520W -
513618N 0045332W -
513230N 0044830W -
512900N 0045432W -
512900N 0050330W -
513130N 0050530W -
513906N 0050320W
Upper limit: 45000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.

Remarks: SI 1986/1834.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0555555556,51.6516666667,13716 -5.0916666667,51.525,13716 -5.0583333333,51.48333333330001,13716 -4.9088888889,51.48333333330001,13716 -4.8083333333,51.5416666667,13716 -4.8922222222,51.605,13716 -4.9222222222,51.605,13716 -4.9279167223,51.61003039919999,13716 -4.9342578797,51.614754824,13716 -4.9410141992,51.6192510473,13716 -4.9481646133,51.62350497,13716 -4.9556867999,51.6275032486,13716 -4.9635572517,51.63123333839999,13716 -4.9717513502,51.63468353299999,13716 -4.9802434429,51.6378430019,13716 -4.9890069249,51.6407018251,13716 -4.9980143228,51.6432510247,13716 -5.0072373821,51.6454825939,13716 -5.0166471575,51.6473895223,13716 -5.0262141049,51.64896581859999,13716 -5.0359081761,51.65020652960001,13716 -5.0456989152,51.6511077564,13716 -5.0555555556,51.6516666667,13716 + + + + +
+ + EGD115A MANORBIER + 513815N 0045012W thence clockwise by the arc of a circle radius 2 NM centred on 513815N 0044700W to
513815N 0044348W -
513815N 0045012W
Upper limit: 27000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.

Remarks: SI 1941/158.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8366666667,51.6375,8229.6 -4.73,51.6375,8229.6 -4.7302715604,51.6408567001,8229.6 -4.7310874734,51.6441790898,8229.6 -4.7324394857,51.6474330816,8229.6 -4.734313836,51.65058528269999,8229.6 -4.7366913916,51.6536033378,8229.6 -4.7395478412,51.6564562626,8229.6 -4.7428539406,51.6591147623,8229.6 -4.746575811,51.66155153370001,8229.6 -4.7506752849,51.6637415465,8229.6 -4.7551102976,51.6656623018,8229.6 -4.7598353191,51.66729406410001,8229.6 -4.7648018228,51.6686200655,8229.6 -4.7699587861,51.6696266787,8229.6 -4.7752532169,51.6703035578,8229.6 -4.7806307011,51.6706437457,8229.6 -4.7860359656,51.6706437457,8229.6 -4.7914134498,51.6703035578,8229.6 -4.7967078805,51.6696266787,8229.6 -4.8018648438,51.6686200655,8229.6 -4.8068313476,51.66729406410001,8229.6 -4.811556369,51.6656623018,8229.6 -4.8159913818,51.6637415465,8229.6 -4.8200908557,51.66155153370001,8229.6 -4.8238127261,51.6591147623,8229.6 -4.8271188255,51.6564562626,8229.6 -4.829975275,51.6536033378,8229.6 -4.8323528307,51.65058528269999,8229.6 -4.834227181,51.6474330816,8229.6 -4.8355791933,51.6441790898,8229.6 -4.8363951063,51.6408567001,8229.6 -4.8366666667,51.6375,8229.6 + + + + +
+ + EGD115B MANORBIER + 513815N 0045012W -
513815N 0044348W -
513345N 0043019W thence clockwise by the arc of a circle radius 11.34 NM centred on 513815N 0044700W to
513208N 0050218W -
513815N 0045012W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.

Remarks: SI 1941/158.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8366666667,51.6375,15240 -5.0383333333,51.5355555556,15240 -5.0309417218,51.5288043613,15240 -5.0231463892,51.5222339864,15240 -5.0149045172,51.51587978300001,15240 -5.0062316321,51.509753581,15240 -4.9971440429,51.5038667816,15240 -4.9876588105,51.49823033580001,15240 -4.9777937157,51.4928547252,15240 -4.9675672259,51.4877499426,15240 -4.9569984611,51.48292547439999,15240 -4.946107158,51.478390283,15240 -4.934913634,51.4741527909,15240 -4.9234387502,51.4702208656,15240 -4.9117038729,51.4666018052,15240 -4.8997308346,51.4633023255,15240 -4.8875418953,51.460328548,15240 -4.8751597012,51.4576859887,15240 -4.8626072445,51.4553795484,15240 -4.849907822,51.4534135038,15240 -4.8370849928,51.4517915,15240 -4.8241625367,51.4505165438,15240 -4.8111644114,51.4495909985,15240 -4.7981147096,51.4490165796,15240 -4.785037616,51.4487943517,15240 -4.7719573642,51.4489247268,15240 -4.7588981934,51.449407463,15240 -4.7458843053,51.4502416659,15240 -4.7329398206,51.45142578910001,15240 -4.7200887363,51.4529576379,15240 -4.7073548826,51.4548343726,15240 -4.6947618804,51.4570525138,15240 -4.6823330987,51.4596079487,15240 -4.6700916132,51.46249593820001,15240 -4.6580601642,51.46571112580001,15240 -4.646261116,51.46924754669999,15240 -4.6347164165,51.4730986389,15240 -4.6234475573,51.4772572546,15240 -4.6124755347,51.48171567349999,15240 -4.6018208114,51.4864656162,15240 -4.5915032789,51.4914982594,15240 -4.5815422215,51.4968042517,15240 -4.5719562797,51.5023737305,15240 -4.5627634166,51.50819633990001,15240 -4.5539808837,51.514261249,15240 -4.5456251891,51.52055717219999,15240 -4.5377120657,51.5270723892,15240 -4.5302564419,51.53379476650001,15240 -4.5232724124,51.5407117792,15240 -4.5167732117,51.5478105344,15240 -4.5107711877,51.5550777941,15240 -4.5052777778,51.5625,15240 -4.73,51.6375,15240 -4.8366666667,51.6375,15240 + + + + +
+ + EGD117 PENDINE + 513510N 0042400W -
513629N 0043752W -
513958N 0043743W -
514515N 0043300W -
514524N 0042517W -
514445N 0042400W -
513510N 0042400W
Upper limit: 27000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 23,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 27,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information: Range Control, Tel: 01994-452240.

Remarks: SI 1973/1627. UAS BVLOS will not be conducted above 10,000 FT ALT.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4,51.5861111111,8229.6 -4.4,51.7458333333,8229.6 -4.4213888889,51.7566666667,8229.6 -4.55,51.7541666667,8229.6 -4.6286111111,51.66611111110001,8229.6 -4.6311111111,51.6080555556,8229.6 -4.4,51.5861111111,8229.6 + + + + +
+ + EGD118 PEMBREY + 514625N 0042400W thence clockwise by the arc of a circle radius 3.5 NM centred on 514313N 0042144W to
514001N 0042400W -
514625N 0042400W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 12,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS / SUAAIS: Pembrey Range on 122.750 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01554-892205.

Remarks: Associated aircraft operations outside area boundary; 122.750 MHz is a common frequency also used by Holbeach and Donna Nook AWRs. Ensure crossing clearance request is specific to Pembrey AWR. UAS BVLOS will not be conducted above 9000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4,51.7736111111,7010.400000000001 -4.4,51.6669444444,7010.400000000001 -4.3932089918,51.66529097230001,7010.400000000001 -4.386237853,51.6639604701,7010.400000000001 -4.3791217654,51.6629707362,7010.400000000001 -4.3719036854,51.6623277443,7010.400000000001 -4.3646271782,51.6620353749,7010.400000000001 -4.3573361576,51.6620953927,7010.400000000001 -4.3500746236,51.66250743539999,7010.400000000001 -4.3428864007,51.6632690162,7010.400000000001 -4.3358148759,51.6643755387,7010.400000000001 -4.3289027398,51.6658203243,7010.400000000001 -4.3221917315,51.6675946518,7010.400000000001 -4.3157223893,51.6696878099,7010.400000000001 -4.3095338075,51.67208716079999,7010.400000000001 -4.3036634025,51.674778216,7010.400000000001 -4.2981466874,51.67774472279999,7010.400000000001 -4.2930170582,51.68096876169999,7010.400000000001 -4.2883055923,51.6844308533,7010.400000000001 -4.2840408602,51.6881100757,7010.400000000001 -4.2802487514,51.6919841894,7010.400000000001 -4.2769523168,51.6960297713,7010.400000000001 -4.2741716265,51.700222355,7010.400000000001 -4.2719236467,51.7045365786,7010.400000000001 -4.2702221333,51.7089463366,7010.400000000001 -4.2690775454,51.7134249384,7010.400000000001 -4.2684969787,51.71794526830001,7010.400000000001 -4.268484118,51.7224799502,7010.400000000001 -4.2690392114,51.7270015129,7010.400000000001 -4.2701590641,51.7314825564,7010.400000000001 -4.2718370543,51.7358959184,7010.400000000001 -4.274063169,51.7402148389,7010.400000000001 -4.2768240608,51.7444131231,7010.400000000001 -4.2801031259,51.7484653009,7010.400000000001 -4.2838806013,51.7523467816,7010.400000000001 -4.2881336823,51.7560340046,7010.400000000001 -4.2928366585,51.75950458270001,7010.400000000001 -4.2979610682,51.762737439,7010.400000000001 -4.3034758704,51.7657129363,7010.400000000001 -4.3093476325,51.76841299660001,7010.400000000001 -4.3155407334,51.7708212126,7010.400000000001 -4.3220175804,51.7729229477,7010.400000000001 -4.328738839,51.7747054264,7010.400000000001 -4.3356636736,51.7761578122,7010.400000000001 -4.3427499972,51.77727127450001,7010.400000000001 -4.3499547303,51.778039043,7010.400000000001 -4.3572340651,51.7784564488,7010.400000000001 -4.364543735,51.7785209536,7010.400000000001 -4.3718392867,51.7782321652,7010.400000000001 -4.3790763538,51.7775918398,7010.400000000001 -4.3862109299,51.7766038711,7010.400000000001 -4.3931996384,51.7752742668,7010.400000000001 -4.4,51.7736111111,7010.400000000001 + + + + +
+ + EGD119 BRIDGWATER BAY + A circle, 4 NM radius, centred at 511224N 0031353W
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Yeovilton APP on 127.350 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information: RNAS Yeovilton Air Operations, Tel: 01935-455497. Booking: RNAS Yeovilton Air Weapons Supply, Tel: 01935-455449. Range Tower when manned, Tel: 01278-741337.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2313888889,51.2732537142,1524 -3.2391376971,51.27307582360001,1524 -3.2468449835,51.27254310509999,1524 -3.254469451499999,51.27165841290001,1524 -3.2619702543,51.2704264874,1524 -3.2693072156,51.26885392860001,1524 -3.2764410482,51.266949161,1524 -3.2833335658,51.2647223876,1524 -3.2899478902,51.2621855343,1524 -3.2962486495,51.2593521862,1524 -3.3022021691,51.2562375131,1524 -3.3077766525,51.2528581878,1524 -3.3129423514,51.24923229629999,1524 -3.3176717247,51.2453792395,1524 -3.321939585,51.241319629,1524 -3.3257232319,51.2370751757,1524 -3.3290025716,51.2326685731,1524 -3.3317602224,51.2281233748,1524 -3.333981604299999,51.2234638686,1524 -3.335655014599999,51.2187149454,1524 -3.336771687,51.2139019661,1524 -3.3373258345,51.209050626,1524 -3.337314677,51.2041868169,1524 -3.336738452300001,51.1993364891,1524 -3.3356004111,51.1945255131,1524 -3.3339067956,51.1897795412,1524 -3.331666803,51.1851238715,1524 -3.3288925326,51.1805833133,1524 -3.3255989185,51.17618205519999,1524 -3.3218036468,51.1719435371,1524 -3.317527058900001,51.1678903259,1524 -3.3127920413,51.16404399629999,1524 -3.3076239017,51.1604250162,1524 -3.3020502333,51.15705263949999,1524 -3.2961007668,51.15394480390001,1524 -3.2898072125,51.1511180366,1524 -3.283203091599999,51.14858736719999,1524 -3.276323558100001,51.14636624869999,1524 -3.2692052139,51.1444664867,1524 -3.2618859148,51.1428981776,1524 -3.254404571999999,51.1416696551,1524 -3.2468009466,51.1407874469,1524 -3.2391154415,51.14025624010001,1524 -3.2313888889,51.14007885709999,1524 -3.2236623363,51.14025624010001,1524 -3.2159768312,51.1407874469,1524 -3.2083732058,51.1416696551,1524 -3.200891862899999,51.1428981776,1524 -3.1935725639,51.1444664867,1524 -3.1864542197,51.14636624869999,1524 -3.1795746862,51.14858736719999,1524 -3.1729705652,51.1511180366,1524 -3.166677011,51.15394480390001,1524 -3.1607275445,51.15705263949999,1524 -3.155153876,51.1604250162,1524 -3.149985736500001,51.16404399629999,1524 -3.1452507189,51.1678903259,1524 -3.140974131000001,51.1719435371,1524 -3.1371788593,51.17618205519999,1524 -3.1338852452,51.1805833133,1524 -3.1311109748,51.1851238715,1524 -3.1288709822,51.1897795412,1524 -3.1271773667,51.1945255131,1524 -3.1260393255,51.1993364891,1524 -3.1254631008,51.2041868169,1524 -3.125451943299999,51.209050626,1524 -3.1260060908,51.2139019661,1524 -3.1271227631,51.2187149454,1524 -3.1287961735,51.2234638686,1524 -3.1310175554,51.2281233748,1524 -3.1337752061,51.2326685731,1524 -3.1370545459,51.2370751757,1524 -3.1408381928,51.241319629,1524 -3.145106053,51.2453792395,1524 -3.1498354263,51.24923229629999,1524 -3.1550011252,51.2528581878,1524 -3.1605756087,51.2562375131,1524 -3.1665291283,51.2593521862,1524 -3.1728298876,51.2621855343,1524 -3.1794442119,51.2647223876,1524 -3.1863367296,51.266949161,1524 -3.1934705622,51.26885392860001,1524 -3.2008075235,51.2704264874,1524 -3.2083083262,51.27165841290001,1524 -3.2159327943,51.27254310509999,1524 -3.2236400807,51.27307582360001,1524 -3.2313888889,51.2732537142,1524 + + + + +
+ + EGD120 BOSCOMBE DOWN + 511052N 0014802W -
511059N 0014641W -
511044N 0014308W -
511105N 0014228W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510844N 0014110W -
510801N 0014248W -
510730N 0014248W -
510646N 0014409W -
510746N 0014819W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to -
511052N 0014802W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: This Danger Area is contained within the extant Boscombe Down ATZ; all regulations associated with flight within an ATZ remain applicable. Upper limit is expressed by reference to height, based on Boscombe Down QFE (identical to ATZ upper limit).

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8005555556,51.18111111110001,762 -1.804205638,51.1781799843,762 -1.807520014,51.1751003506,762 -1.810383437,51.1718469736,762 -1.8127731156,51.1684458589,762 -1.8146700582,51.1649241872,762 -1.8160592224,51.1613100965,762 -1.8169296313,51.1576324567,762 -1.8172744577,51.1539206381,762 -1.817091075,51.15020427749999,762 -1.8163810737,51.1465130403,762 -1.815150245,51.1428763847,762 -1.8134085306,51.13932332660001,762 -1.8111699394,51.1358822079,762 -1.8084524327,51.1325804719,762 -1.8052777778,51.1294444444,762 -1.7358333333,51.1127777778,762 -1.7133333333,51.125,762 -1.7133333333,51.1336111111,762 -1.6861111111,51.14555555559999,762 -1.6853632646,51.1491417891,762 -1.6850302822,51.1527499945,762 -1.6851969823,51.1563627495,762 -1.6858622209,51.15995273230001,762 -1.6870210811,51.16349278709999,762 -1.6886649068,51.1669561299,762 -1.6907813654,51.1703165508,762 -1.6933545375,51.1735486135,762 -1.6963650348,51.17662784809999,762 -1.6997901449,51.17953093689999,762 -1.7036040013,51.18223589200001,762 -1.7077777778,51.1847222222,762 -1.7188888889,51.1788888889,762 -1.7780555556,51.1830555556,762 -1.8005555556,51.18111111110001,762 + + + + +
+ + EGD122A WESSEX WEST + 511329N 0021149W -
511106N 0020713W -
511006N 0015702W -
510125N 0015702W -
505938N 0020714W -
510120N 0021149W -
511329N 0021149W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122A and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.02222222220001,4876.8 -2.1205555556,50.9938888889,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -2.1202777778,51.185,4876.8 -2.1969444444,51.2247222222,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.02222222220001,2438.4 -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.02222222220001,2438.4 -2.1969444444,51.02222222220001,4876.8 -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.2247222222,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.02222222220001,2438.4 -2.1205555556,50.9938888889,2438.4 -2.1205555556,50.9938888889,4876.8 -2.1969444444,51.02222222220001,4876.8 -2.1969444444,51.02222222220001,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -2.1205555556,50.9938888889,4876.8 -2.1205555556,50.9938888889,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1202777778,51.185,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.2247222222,4876.8 -2.1202777778,51.185,4876.8 -2.1202777778,51.185,2438.4 + + + + + +
+ + EGD122B WESSEX CENTRAL + 511059N 0014641W -
511044N 0014308W -
510357N 0014230W -
510125N 0015702W -
511006N 0015702W -
511059N 0014641W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122B and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7780555556,51.1830555556,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.7780555556,51.1830555556,4876.8 -1.7780555556,51.1830555556,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 -1.7780555556,51.1830555556,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + +
+ + EGD122C WESSEX EAST + 511335N 0013725W -
511236N 0013044W -
510527N 0013342W -
510357N 0014230W -
511044N 0014308W -
511233N 0013942W -
511247N 0013759W -
511335N 0013725W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122C and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,4876.8 -1.6330555556,51.21305555559999,4876.8 -1.6616666667,51.2091666667,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5122222222,51.21000000000001,4876.8 -1.6236111111,51.22638888889999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,2438.4 -1.6330555556,51.21305555559999,2438.4 -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21000000000001,2438.4 -1.6236111111,51.22638888889999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,2438.4 -1.6330555556,51.21305555559999,2438.4 -1.6330555556,51.21305555559999,4876.8 -1.6236111111,51.22638888889999,4876.8 -1.6236111111,51.22638888889999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6330555556,51.21305555559999,2438.4 -1.6616666667,51.2091666667,2438.4 -1.6616666667,51.2091666667,4876.8 -1.6330555556,51.21305555559999,4876.8 -1.6330555556,51.21305555559999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.6616666667,51.2091666667,4876.8 -1.6616666667,51.2091666667,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5616666667,51.0908333333,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21000000000001,2438.4 -1.5122222222,51.21000000000001,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5616666667,51.0908333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.5122222222,51.21000000000001,2438.4 -1.6236111111,51.22638888889999,2438.4 -1.6236111111,51.22638888889999,4876.8 -1.5122222222,51.21000000000001,4876.8 -1.5122222222,51.21000000000001,2438.4 + + + + + +
+ + EGD123 IMBER + 511724N 0020107W -
511339N 0015746W -
511348N 0015705W -
511023N 0015325W -
511006N 0015702W -
511106N 0020713W -
511329N 0021149W -
511516N 0020939W -
511705N 0020312W -
511724N 0020107W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 3000 FT ALT H24.

Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730 when open.

Remarks: SI 1963/1293, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0186111111,51.29,15240 -2.0533333333,51.2847222222,15240 -2.1608333333,51.25444444439999,15240 -2.1969444444,51.2247222222,15240 -2.1202777778,51.185,15240 -1.9505555556,51.1683333333,15240 -1.8902777778,51.1730555556,15240 -1.9513888889,51.23,15240 -1.9627777778,51.2275,15240 -2.0186111111,51.29,15240 + + + + +
+ + EGD124 LAVINGTON + A circle, 1.5 NM radius, centred at 511527N 0015812W
Upper limit: UNL
Lower limit: SFC
Class: AMC Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710.

Remarks: SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.97,51.282470014,30449.52 -1.9747091708,51.2822946576,30449.52 -1.9793521288,51.2817710539,30449.52 -1.9838635968,51.2809065647,30449.52 -1.988180155,51.2797133442,30449.52 -1.992241136,51.2782081673,30449.52 -1.995989481,51.2764121923,30449.52 -1.9993725434,51.2743506631,30449.52 -2.0023428293,51.2720525523,30449.52 -2.0048586647,51.2695501529,30449.52 -2.0068847788,51.266878623,30449.52 -2.008392797,51.264075491,30449.52 -2.009361635,51.26118012690001,30449.52 -2.0097777904,51.2582331885,30449.52 -2.0096355267,51.2552760504,30449.52 -2.0089369474,51.2523502221,30449.52 -2.0076919612,51.2494967662,30449.52 -2.005918137,51.246755722,30449.52 -2.0036404518,51.2441655445,30449.52 -2.0008909363,51.24176256610001,30449.52 -1.9977082216,51.23958048779999,30449.52 -1.9941369955,51.237649908,30449.52 -1.9902273742,51.235997895,30449.52 -1.9860342001,51.2346476088,30449.52 -1.9816162739,51.2336179772,30449.52 -1.9770355326,51.2329234326,30449.52 -1.972356185,51.23257370950001,30449.52 -1.967643815,51.23257370950001,30449.52 -1.9629644674,51.2329234326,30449.52 -1.9583837261,51.2336179772,30449.52 -1.9539657999,51.2346476088,30449.52 -1.9497726258,51.235997895,30449.52 -1.9458630045,51.237649908,30449.52 -1.9422917784,51.23958048779999,30449.52 -1.9391090637,51.24176256610001,30449.52 -1.9363595482,51.2441655445,30449.52 -1.934081863,51.246755722,30449.52 -1.9323080388,51.2494967662,30449.52 -1.9310630526,51.2523502221,30449.52 -1.9303644733,51.2552760504,30449.52 -1.9302222096,51.2582331885,30449.52 -1.930638365,51.26118012690001,30449.52 -1.931607203,51.264075491,30449.52 -1.9331152212,51.266878623,30449.52 -1.9351413353,51.2695501529,30449.52 -1.9376571707,51.2720525523,30449.52 -1.9406274566,51.2743506631,30449.52 -1.944010519,51.2764121923,30449.52 -1.947758864,51.2782081673,30449.52 -1.951819845,51.2797133442,30449.52 -1.9561364032,51.2809065647,30449.52 -1.9606478712,51.2817710539,30449.52 -1.9652908292,51.2822946576,30449.52 -1.97,51.282470014,30449.52 + + + + +
+ + EGD125 LARKHILL + 511828N 0015004W -
511059N 0014641W -
511023N 0015325W -
511348N 0015705W -
511339N 0015746W -
511724N 0020107W -
511807N 0015635W -
511828N 0015004W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 3000 FT ALT H24.

Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730.

Remarks: SI 1965/1327, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8344444444,51.3077777778,15240 -1.9430555556,51.3019444444,15240 -2.0186111111,51.29,15240 -1.9627777778,51.2275,15240 -1.9513888889,51.23,15240 -1.8902777778,51.1730555556,15240 -1.7780555556,51.1830555556,15240 -1.8344444444,51.3077777778,15240 + + + + +
+ + EGD126 BULFORD + 511621N 0013746W -
511525N 0013606W -
511247N 0013759W -
511233N 0013942W -
511044N 0014308W -
511059N 0014641W -
511351N 0014759W thence clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to
511354N 0014225W -
511621N 0013746W
Upper limit: FL90
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 1400 FT ALT H24.

Vertical Limit OCNL notified up to FL 90 by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 01980-674730 or Boscombe Down ATC, Tel: 01980-663246.

Remarks: SI 1970/1282, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6294444444,51.27250000000001,2743.2 -1.7069444444,51.2316666667,2743.2 -1.715059155,51.2334964065,2743.2 -1.7234325199,51.2348000136,2743.2 -1.7319235049,51.2357586607,2743.2 -1.7404960327,51.2363682739,2743.2 -1.7491136738,51.2366262626,2743.2 -1.757739804,51.2365315304,2743.2 -1.7663377624,51.2360844798,2743.2 -1.7748710099,51.23528701079999,2743.2 -1.7833032865,51.2341425123,2743.2 -1.7915987684,51.2326558475,2743.2 -1.7997222222,51.2308333333,2743.2 -1.7780555556,51.1830555556,2743.2 -1.7188888889,51.1788888889,2743.2 -1.6616666667,51.2091666667,2743.2 -1.6330555556,51.21305555559999,2743.2 -1.6016666667,51.25694444440001,2743.2 -1.6294444444,51.27250000000001,2743.2 + + + + +
+ + EGD127 PORTON + 510552N 0014315W -
510632N 0014435W -
510730N 0014248W -
510801N 0014248W -
511012N 0013750W -
510752N 0013650W -
510703N 0013843W -
510552N 0014315W
Upper limit: 12000 FT MSL
Lower limit: SFC
Class: Vertical Limits:
Upper Limit: ALT 12000 0600-1800 (0500-1700).
Upper Limit: ALT 8000 (OCNL notified to ALT 12000) 1800-0600 (1700-0500).

Activity: Para Dropping / Ordnance, Munitions and Explosives / Electronic/optical hazards / Unmanned Aircraft System (VLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone on 126.700 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: SI 1977/1611.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7208333333,51.0977777778,3657.6 -1.6452777778,51.1175,3657.6 -1.6138888889,51.1311111111,3657.6 -1.6305555556,51.17,3657.6 -1.7133333333,51.1336111111,3657.6 -1.7133333333,51.125,3657.6 -1.7430555556,51.10888888889999,3657.6 -1.7208333333,51.0977777778,3657.6 + + + + +
+ + EGD128 EVERLEIGH + 511852N 0014215W -
511621N 0013746W -
511354N 0014225W thence anti-clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to
511351N 0014759W -
511828N 0015004W -
511852N 0014215W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable

Vertical Limit 1400 FT ALT H24

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information: Salisbury Operations, Tel: 01980-674710 or 674730.

Remarks: SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7041666667,51.3144444444,15240 -1.8344444444,51.3077777778,15240 -1.7997222222,51.2308333333,15240 -1.7915023174,51.2324672241,15240 -1.7832265947,51.2339503473,15240 -1.774814405,51.2350921193,15240 -1.7663014863,51.2358876884,15240 -1.7577240116,51.2363336739,15240 -1.7491184326,51.2364281804,15240 -1.7405213223,51.2361708064,15240 -1.7319692174,51.2355626455,15240 -1.7234984599,51.2346062823,15240 -1.7151450407,51.2333057807,15240 -1.7069444444,51.2316666667,15240 -1.6294444444,51.27250000000001,15240 -1.7041666667,51.3144444444,15240 + + + + +
+ + EGD129 WESTON-ON-THE-GREEN + A circle, 2 NM radius, centred at 515246N 0011320W
Upper limit: FL120
Lower limit: SFC
Class: Activity: Para Dropping.

Service: SUAAIS: Brize Zone on 119.000 MHz. SUACS: Oxford Approach on 125.090 MHz.

Contact: Pre-flight information / Booking: Brize Norton, Tel: 01993-895147.

Remarks: Parachuting activity up to FL 135 may be conducted with London Control (Swanwick) permission. Regular activity SR-SS to FL 85 described in ENR 5.5.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2222222222,51.9127342248,3657.599999999999 -1.2277568724,51.9125576553,3657.599999999999 -1.2332327248,51.9120298224,3657.599999999999 -1.2385916105,51.91115633339999,3657.599999999999 -1.2437766112,51.9099464672,3657.599999999999 -1.2487326672,51.908413075,3657.599999999999 -1.2534071653,51.9065724429,3657.599999999999 -1.2577504999,51.9044441182,3657.599999999999 -1.2617166009,51.9020507004,3657.599999999999 -1.2652634235,51.8994176001,3657.599999999999 -1.268353394,51.89657276789999,3657.599999999999 -1.270953807,51.8935463967,3657.599999999999 -1.2730371699,51.8903705996,3657.599999999999 -1.2745814917,51.8870790687,3657.599999999999 -1.2755705115,51.8837067162,3657.599999999999 -1.2759938668,51.88028930390001,3657.599999999999 -1.2758471977,51.8768630632,3657.599999999999 -1.2751321884,51.8734643111,3657.599999999999 -1.2738565432,51.870129065,3657.599999999999 -1.2720338997,51.8668926615,3657.599999999999 -1.2696836797,51.8637893825,3657.599999999999 -1.2668308788,51.86085209309999,3657.599999999999 -1.2635057979,51.8581118942,3657.599999999999 -1.2597437196,51.8555977944,3657.599999999999 -1.2555845326,51.85333640429999,3657.599999999999 -1.2510723085,51.8513516557,3657.599999999999 -1.2462548354,51.84966455000001,3657.599999999999 -1.2411831132,51.8482929371,3657.599999999999 -1.2359108155,51.8472513271,3657.599999999999 -1.2304937247,51.8465507384,3657.599999999999 -1.2249891449,51.8461985817,3657.599999999999 -1.2194552996,51.8461985817,3657.599999999999 -1.2139507197,51.8465507384,3657.599999999999 -1.2085336289,51.8472513271,3657.599999999999 -1.2032613312,51.8482929371,3657.599999999999 -1.198189609,51.84966455000001,3657.599999999999 -1.193372136,51.8513516557,3657.599999999999 -1.1888599119,51.85333640429999,3657.599999999999 -1.1847007249,51.8555977944,3657.599999999999 -1.1809386465,51.8581118942,3657.599999999999 -1.1776135656,51.86085209309999,3657.599999999999 -1.1747607647,51.8637893825,3657.599999999999 -1.1724105447,51.8668926615,3657.599999999999 -1.1705879013,51.870129065,3657.599999999999 -1.169312256,51.8734643111,3657.599999999999 -1.1685972467,51.8768630632,3657.599999999999 -1.1684505777,51.88028930390001,3657.599999999999 -1.1688739329,51.8837067162,3657.599999999999 -1.1698629527,51.8870790687,3657.599999999999 -1.1714072745,51.8903705996,3657.599999999999 -1.1734906375,51.8935463967,3657.599999999999 -1.1760910505,51.89657276789999,3657.599999999999 -1.179181021,51.8994176001,3657.599999999999 -1.1827278436,51.9020507004,3657.599999999999 -1.1866939445,51.9044441182,3657.599999999999 -1.1910372791,51.9065724429,3657.599999999999 -1.1957117772,51.908413075,3657.599999999999 -1.2006678332,51.9099464672,3657.599999999999 -1.2058528339,51.91115633339999,3657.599999999999 -1.2112117197,51.9120298224,3657.599999999999 -1.2166875721,51.9125576553,3657.599999999999 -1.2222222222,51.9127342248,3657.599999999999 + + + + +
+ + EGD130 LONGMOOR + 510559N 0005213W -
510541N 0004938W -
510446N 0004940W -
510426N 0005301W -
510559N 0005213W
Upper limit: 2300 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1800 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2300 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01420-483405.

Remarks: SI 1982/1179.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8702777778,51.0997222222,701.0400000000001 -0.8836111111,51.0738888889,701.0400000000001 -0.8277777777999999,51.0794444444,701.0400000000001 -0.8272222222000001,51.0947222222,701.0400000000001 -0.8702777778,51.0997222222,701.0400000000001 + + + + +
+ + EGD132 ASH RANGES + 511745N 0003956W -
511623N 0003942W -
511548N 0004034W -
511524N 0004300W -
511606N 0004309W -
511638N 0004259W -
511732N 0004116W -
511745N 0003956W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Remarks: SI 1983/162.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6655555556,51.2958333333,762 -0.6877777778,51.2922222222,762 -0.7163888889,51.27722222220001,762 -0.7191666667000001,51.2683333333,762 -0.7166666667,51.2566666667,762 -0.6761111111,51.2633333333,762 -0.6616666667,51.2730555556,762 -0.6655555556,51.2958333333,762 + + + + +
+ + EGD133A PIRBRIGHT + 511922N 0003907W -
511915N 0003858W -
511828N 0003951W -
511816N 0004028W -
511815N 0004103W -
511830N 0004118W -
511922N 0003907W
Upper limit: 1200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6519444444,51.32277777779999,365.76 -0.6883333333,51.3083333333,365.76 -0.6841666667,51.30416666670001,365.76 -0.6744444444,51.3044444444,365.76 -0.6641666667,51.3077777778,365.76 -0.6494444444,51.3208333333,365.76 -0.6519444444,51.32277777779999,365.76 + + + + +
+ + EGD133B PIRBRIGHT + 512040N 0004029W -
512034N 0003957W -
511922N 0003907W -
511830N 0004118W -
511915N 0004146W -
512019N 0004158W -
512040N 0004029W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1200 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2400 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6747222222,51.3444444444,731.52 -0.6994444444,51.3386111111,731.52 -0.6961111111,51.3208333333,731.52 -0.6883333333,51.3083333333,731.52 -0.6519444444,51.32277777779999,731.52 -0.6658333333000001,51.34277777780001,731.52 -0.6747222222,51.3444444444,731.52 + + + + +
+ + EGD136 SHOEBURYNESS + 513217N 0004804E -
513017N 0005104E -
513030N 0004700E -
513217N 0004804E
Upper limit: 13000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8011111111,51.5380555556,3962.4 0.7833333333,51.5083333333,3962.4 0.8511111111000002,51.50472222219999,3962.4 0.8011111111,51.5380555556,3962.4 + + + + +
+ + EGD138A SHOEBURYNESS + 514000N 0010400E -
514000N 0011613E -
513714N 0011203E -
513714N 0005536E -
514000N 0010400E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 6000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0666666667,51.6666666667,18288 0.9266666667,51.6205555556,18288 1.2008333333,51.6205555556,18288 1.2702777778,51.6666666667,18288 1.0666666667,51.6666666667,18288 + + + + +
+ + EGD138B SHOEBURYNESS + 514200N 0011124E -
514200N 0011912E -
514000N 0011613E -
514000N 0010400E -
514200N 0011124E
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.19,51.7,1524 1.0666666667,51.6666666667,1524 1.2702777778,51.6666666667,1524 1.32,51.7,1524 1.19,51.7,1524 + + + + +
+ + EGD138C SHOEBURYNESS + 513700N 0005455E -
513755N 0005740E -
513638N 0005850E -
513544N 0005620E -
513700N 0005455E
Upper limit: 6000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: May be activated at the same time as EGD138A and/or EGD138D as a separate activity.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9152777778000001,51.6166666667,1828.8 0.9388888889,51.5955555556,1828.8 0.9805555555999999,51.6105555556,1828.8 0.9611111111,51.63194444440001,1828.8 0.9152777778000001,51.6166666667,1828.8 + + + + +
+ + EGD138D SHOEBURYNESS + 513714N 0005536E -
513714N 0011203E -
513000N 0005300E -
513009N 0005115E -
513217N 0004804E -
513400N 0005000E -
513500N 0005018E -
513541N 0005016E - then along the north coast of Foulness Island to
513700N 0005455E -
513714N 0005536E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 13,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9266666667,51.6205555556,18288 0.9152777778000001,51.6166666667,18288 0.915875,51.61495,18288 0.913075,51.6141194444,18288 0.9085638888999999,51.61360000000001,18288 0.9064277777999999,51.61410277779999,18288 0.9046694444,51.6136972222,18288 0.9015722222,51.6126944444,18288 0.8996138888999999,51.61373333329999,18288 0.8951472221999999,51.6139333333,18288 0.8891527778,51.6150694444,18288 0.877525,51.6140055556,18288 0.8742555556,51.61255833330001,18288 0.87235,51.6098166667,18288 0.8720472222,51.6004694444,18288 0.87065,51.5966361111,18288 0.8677638889000001,51.5943666667,18288 0.8625527777999999,51.5918861111,18288 0.8590694444,51.5916111111,18288 0.8508555556,51.5919,18288 0.8451333333,51.5927583333,18288 0.8405138889,51.59278055560001,18288 0.8377777778000001,51.5947222222,18288 0.8383333333,51.58333333329999,18288 0.8333333333000001,51.5666666667,18288 0.8011111111,51.5380555556,18288 0.8541666667,51.50249999999999,18288 0.8833333333,51.5,18288 1.2008333333,51.6205555556,18288 0.9266666667,51.6205555556,18288 + + + + +
+ + EGD139 FINGRINGHOE + 515000N 0005458E -
514954N 0005852E -
514833N 0005848E -
514839N 0005452E -
515000N 0005458E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01206-736149.

Remarks: SI 1974/665.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9161111111,51.83333333329999,609.6 0.9144444443999998,51.8108333333,609.6 0.98,51.8091666667,609.6 0.9811111111000002,51.8316666667,609.6 0.9161111111,51.83333333329999,609.6 + + + + +
+ + EGD141 HYTHE RANGES + 510419N 0010426E -
510212N 0010531E -
510120N 0010148E -
510158N 0010111E -
510323N 0010214E -
510419N 0010426E
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225879.

Remarks: SI 1966/814.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0738888889,51.0719444444,975.36 1.0372222222,51.0563888889,975.36 1.0197222222,51.03277777780001,975.36 1.03,51.02222222220001,975.36 1.0919444444,51.0366666667,975.36 1.0738888889,51.0719444444,975.36 + + + + +
+ + EGD147 PONTRILAS + A circle, 2 NM radius, centred at 515800N 0025300W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: Activity: Para Dropping / Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information 124.750 MHz.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8833333333,51.999955951,3048 -2.8888787335,51.9997793836,3048 -2.8943652213,51.9992515574,3048 -2.8997345145,51.9983780795,3048 -2.9049295838,51.9971682287,3048 -2.9098952622,51.99563485620001,3048 -2.9145788343,51.9937942479,3048 -2.9189305979,51.9916659511,3048 -2.9229043934,51.98927256490001,3048 -2.9264580946,51.9866395,3048 -2.9295540548,51.9837947065,3048 -2.9321595054,51.9807683771,3048 -2.9342469009,51.9775926246,3048 -2.9357942078,51.9743011406,3048 -2.9367851343,51.970928837,3048 -2.9372092981,51.967511475,3048 -2.9370623318,51.9640852856,3048 -2.9363459229,51.96068658519999,3048 -2.9350677915,51.9573513906,3048 -2.933241602,51.9541150377,3048 -2.9308868144,51.9510118081,3048 -2.928028473,51.948074566,3048 -2.924696937899999,51.9453344117,3048 -2.9209275601,51.94282035329999,3048 -2.9167603059,51.9405590008,3048 -2.9122393324,51.93857428559999,3048 -2.907412519999999,51.9368872085,3048 -2.9023309674,51.9355156188,3048 -2.8970484519,51.9344740267,3048 -2.8916208636,51.93377345010001,3048 -2.8861056174,51.9334212994,3048 -2.8805610492,51.9334212994,3048 -2.8750458031,51.93377345010001,3048 -2.8696182148,51.9344740267,3048 -2.8643356993,51.9355156188,3048 -2.8592541466,51.9368872085,3048 -2.8544273343,51.93857428559999,3048 -2.8499063607,51.9405590008,3048 -2.8457391065,51.94282035329999,3048 -2.8419697288,51.9453344117,3048 -2.8386381936,51.948074566,3048 -2.8357798523,51.9510118081,3048 -2.8334250647,51.9541150377,3048 -2.8315988752,51.9573513906,3048 -2.8303207437,51.96068658519999,3048 -2.8296043349,51.9640852856,3048 -2.8294573685,51.967511475,3048 -2.8298815324,51.970928837,3048 -2.8308724589,51.9743011406,3048 -2.832419765800001,51.9775926246,3048 -2.8345071613,51.9807683771,3048 -2.8371126119,51.9837947065,3048 -2.8402085721,51.9866395,3048 -2.8437622732,51.98927256490001,3048 -2.8477360688,51.9916659511,3048 -2.8520878324,51.9937942479,3048 -2.8567714045,51.99563485620001,3048 -2.8617370829,51.9971682287,3048 -2.8669321522,51.9983780795,3048 -2.872301445400001,51.9992515574,3048 -2.8777879332,51.9997793836,3048 -2.8833333333,51.999955951,3048 + + + + +
+ + EGD148 KEEVIL + 511744N 0021016W -
511937N 0020745W -
512055N 0020410W -
511946N 0020305W -
511705N 0020312W -
511602N 0020657W -
511701N 0020929W -
511744N 0021016W
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710.

Danger Area Authority: JHC HQ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1710333333,51.29568888890001,975.36 -2.1580805556,51.2835916667,975.36 -2.11575,51.2672444444,975.36 -2.0533333333,51.2847222222,975.36 -2.0513416667,51.3294194444,975.36 -2.0694666667,51.34871666669999,975.36 -2.1292833333,51.3269444444,975.36 -2.1710333333,51.29568888890001,975.36 + + + + +
+ + EGD201A ABERPORTH + 523427N 0052148W -
520903N 0050057W -
521000N 0050822W -
521307N 0051616W -
522013N 0052151W -
523427N 0052148W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3634016667,52.5740336111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.2711694444,52.2185361111,30449.52 -5.13935,52.1667388889,30449.52 -5.0158333333,52.15083333330001,30449.52 -5.3634016667,52.5740336111,30449.52 + + + + +
+ + EGD201B ABERPORTH + 530300N 0053000W -
531500N 0053000W -
532315N 0051017W -
532255N 0050000W -
531200N 0050000W -
530715N 0045319W -
530300N 0045319W following the line of latitude to -
530300N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.0108888889,53.05,30449.52 -4.8886111111,53.05,30449.52 -4.8886111111,53.12083333329999,30449.52 -5,53.2,30449.52 -5,53.3819444444,30449.52 -5.1713888889,53.3875,30449.52 -5.5,53.25,30449.52 -5.5,53.05,30449.52 + + + + +
+ + EGD201C ABERPORTH + 525019N 0045319W -
524500N 0044018W -
524500N 0045319W -
525019N 0045319W
Upper limit: UNL
Lower limit: FL145
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,30449.52 -4.8886111111,52.75,30449.52 -4.6716305556,52.75,30449.52 -4.8886111111,52.83873333329999,30449.52 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.8886111111,52.83873333329999,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.75,4419.6 -4.8886111111,52.75,30449.52 -4.8886111111,52.83873333329999,30449.52 -4.8886111111,52.83873333329999,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.6716305556,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,52.75,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.6716305556,52.75,4419.6 -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.83873333329999,30449.52 -4.6716305556,52.75,30449.52 -4.6716305556,52.75,4419.6 + + + + + +
+ + EGD201D ABERPORTH + 531035N 0053000W -
530300N 0051612W following the line of latitude to -
530300N 0053000W -
531035N 0053000W
Upper limit: UNL
Lower limit: FL55
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,30449.52 -5.5,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.2698722222,53.05,30449.52 -5.5,53.1764722222,30449.52 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.5,53.05,30449.52 -5.5,53.1764722222,30449.52 -5.5,53.1764722222,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.3849361111,53.05,30449.52 -5.5,53.05,30449.52 -5.5,53.05,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.2698722222,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.3849361111,53.05,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 -5.5,53.1764722222,30449.52 -5.2698722222,53.05,30449.52 -5.2698722222,53.05,1676.4 + + + + + +
+ + EGD201F ABERPORTH + 521236N 0052244W -
521000N 0050822W -
520903N 0050057W -
520840N 0043847W -
520612N 0044900W -
520816N 0051829W -
521236N 0052244W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3787709722,52.2100607222,30449.52 -5.3080555556,52.1377777778,30449.52 -4.8166666667,52.1033333333,30449.52 -4.646375,52.14435,30449.52 -5.0158333333,52.15083333330001,30449.52 -5.13935,52.1667388889,30449.52 -5.3787709722,52.2100607222,30449.52 + + + + +
+ + EGD201G ABERPORTH + 524417N 0053000W -
523427N 0052148W -
522013N 0052151W -
521307N 0051616W -
521000N 0050822W -
521236N 0052244W -
522000N 0053000W -
524417N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,52.73805555559999,30449.52 -5.5,52.3333333333,30449.52 -5.3787709722,52.2100607222,30449.52 -5.13935,52.1667388889,30449.52 -5.2711694444,52.2185361111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.3634016667,52.5740336111,30449.52 -5.5,52.73805555559999,30449.52 + + + + +
+ + EGD201H ABERPORTH + 523000N 0051806W following the line of latitude to -
523000N 0041200W -
521600N 0041200W -
521000N 0042942W -
520848N 0042904W -
520702N 0043810W -
520840N 0043847W -
520903N 0050057W -
523000N 0051806W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3016805556,52.5,30449.52 -5.0158333333,52.15083333330001,30449.52 -4.646375,52.14435,30449.52 -4.6360805556,52.1171138889,30449.52 -4.4845083333,52.1468,30449.52 -4.495,52.16666666670001,30449.52 -4.2,52.26666666669999,30449.52 -4.2,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.8885503472,52.5,30449.52 -5.0262604167,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.3016805556,52.5,30449.52 + + + + +
+ + EGD201J ABERPORTH + 530300N 0053000W following the line of latitude to -
530300N 0045319W -
524500N 0045319W following the line of latitude to -
524500N 0044018W -
523316N 0041200W -
523000N 0041200W following the line of latitude to -
523000N 0051806W -
524417N 0053000W -
530300N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,53.05,30449.52 -5.5,52.73805555559999,30449.52 -5.3016805556,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.0262604167,52.5,30449.52 -4.8885503472,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.2,52.5,30449.52 -4.2,52.5544888889,30449.52 -4.6716666667,52.75,30449.52 -4.7801388889,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,53.05,30449.52 -5.0108888889,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.5,53.05,30449.52 + + + + +
+ + EGD201K ABERPORTH + 522000N 0053000W -
520816N 0051829W -
521038N 0053000W -
522000N 0053000W
Upper limit: FL145
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,52.3333333333,4419.6 -5.5,52.17722222219999,4419.6 -5.3080555556,52.1377777778,4419.6 -5.5,52.3333333333,4419.6 + + + + +
+ + EGD202A WEST WALES + 521250N 0042121W -
521600N 0041200W -
521545N 0040958W -
520135N 0041430W -
520019N 0042519W -
521250N 0042121W
Upper limit: FL100
Lower limit: FL60
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202A and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.4219444444,52.0052777778,3048 -4.2416666667,52.0263888889,3048 -4.1661111111,52.2625,3048 -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,1828.8 -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.2,52.26666666669999,1828.8 -4.3558333333,52.21388888889999,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,1828.8 -4.4219444444,52.0052777778,1828.8 -4.4219444444,52.0052777778,3048 -4.3558333333,52.21388888889999,3048 -4.3558333333,52.21388888889999,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.2416666667,52.0263888889,3048 -4.4219444444,52.0052777778,3048 -4.4219444444,52.0052777778,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.1661111111,52.2625,3048 -4.2416666667,52.0263888889,3048 -4.2416666667,52.0263888889,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1661111111,52.2625,1828.8 -4.2,52.26666666669999,1828.8 -4.2,52.26666666669999,3048 -4.1661111111,52.2625,3048 -4.1661111111,52.2625,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.2,52.26666666669999,1828.8 -4.3558333333,52.21388888889999,1828.8 -4.3558333333,52.21388888889999,3048 -4.2,52.26666666669999,3048 -4.2,52.26666666669999,1828.8 + + + + + +
+ + EGD202B WEST WALES + 521250N 0042121W -
521600N 0041200W -
521433N 0040004W -
520320N 0040343W -
520545N 0042336W -
521250N 0042121W
Upper limit: FL225
Lower limit: FL100
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202B and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,6858 -4.3933333333,52.09583333330001,6858 -4.0619444444,52.0555555556,6858 -4.0011111111,52.24249999999999,6858 -4.2,52.26666666669999,6858 -4.3558333333,52.21388888889999,6858 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.3933333333,52.09583333330001,3048 -4.0619444444,52.0555555556,3048 -4.0011111111,52.24249999999999,3048 -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.3933333333,52.09583333330001,3048 -4.3933333333,52.09583333330001,6858 -4.3558333333,52.21388888889999,6858 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3933333333,52.09583333330001,3048 -4.0619444444,52.0555555556,3048 -4.0619444444,52.0555555556,6858 -4.3933333333,52.09583333330001,6858 -4.3933333333,52.09583333330001,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0619444444,52.0555555556,3048 -4.0011111111,52.24249999999999,3048 -4.0011111111,52.24249999999999,6858 -4.0619444444,52.0555555556,6858 -4.0619444444,52.0555555556,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.2,52.26666666669999,3048 -4.2,52.26666666669999,6858 -4.0011111111,52.24249999999999,6858 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 -4.3558333333,52.21388888889999,6858 -4.2,52.26666666669999,6858 -4.2,52.26666666669999,3048 + + + + + +
+ + EGD202C WEST WALES + 521433N 0040004W -
521047N 0033002W -
520721N 0033015W -
520501N 0033532W -
520211N 0034019W -
520030N 0034053W -
520320N 0040343W -
521433N 0040004W
Upper limit: FL225
Lower limit: FL100
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202C and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,6858 -4.0619444444,52.0555555556,6858 -3.6813888889,52.0083333333,6858 -3.6719444444,52.03638888890001,6858 -3.5922222222,52.08361111109999,6858 -3.504166666700001,52.1225,6858 -3.5005555556,52.17972222220001,6858 -4.0011111111,52.24249999999999,6858 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.0619444444,52.0555555556,3048 -3.6813888889,52.0083333333,3048 -3.6719444444,52.03638888890001,3048 -3.5922222222,52.08361111109999,3048 -3.504166666700001,52.1225,3048 -3.5005555556,52.17972222220001,3048 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.0619444444,52.0555555556,3048 -4.0619444444,52.0555555556,6858 -4.0011111111,52.24249999999999,6858 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0619444444,52.0555555556,3048 -3.6813888889,52.0083333333,3048 -3.6813888889,52.0083333333,6858 -4.0619444444,52.0555555556,6858 -4.0619444444,52.0555555556,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.6813888889,52.0083333333,3048 -3.6719444444,52.03638888890001,3048 -3.6719444444,52.03638888890001,6858 -3.6813888889,52.0083333333,6858 -3.6813888889,52.0083333333,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.6719444444,52.03638888890001,3048 -3.5922222222,52.08361111109999,3048 -3.5922222222,52.08361111109999,6858 -3.6719444444,52.03638888890001,6858 -3.6719444444,52.03638888890001,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.5922222222,52.08361111109999,3048 -3.504166666700001,52.1225,3048 -3.504166666700001,52.1225,6858 -3.5922222222,52.08361111109999,6858 -3.5922222222,52.08361111109999,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.504166666700001,52.1225,3048 -3.5005555556,52.17972222220001,3048 -3.5005555556,52.17972222220001,6858 -3.504166666700001,52.1225,6858 -3.504166666700001,52.1225,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.5005555556,52.17972222220001,3048 -4.0011111111,52.24249999999999,3048 -4.0011111111,52.24249999999999,6858 -3.5005555556,52.17972222220001,6858 -3.5005555556,52.17972222220001,3048 + + + + + +
+ + EGD202D WEST WALES + 520840N 0043847W -
520702N 0043810W -
520848N 0042904W -
521000N 0042942W -
521250N 0042121W -
520019N 0042519W -
515840N 0043902W -
520555N 0044130W thence clockwise by the arc of a circle radius 5 NM centred on 520653N 0043334W to
520801N 0044128W -
520840N 0043847W
Upper limit: FL125
Lower limit: SFC
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202D and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.646375,52.14435,3810 -4.6911111111,52.1336111111,3810 -4.6923695661,52.1286290972,3810 -4.6934867815,52.1236458923,3810 -4.6941112708,52.118630173,3810 -4.6942409049,52.1136003736,3810 -4.6938753744,52.10857497359999,3810 -4.6930161885,52.1035724304,3810 -4.6916666667,52.0986111111,3810 -4.6505555556,51.9777777778,3810 -4.4219444444,52.0052777778,3810 -4.3558333333,52.21388888889999,3810 -4.495,52.16666666670001,3810 -4.4845083333,52.1468,3810 -4.6360805556,52.1171138889,3810 -4.646375,52.14435,3810 + + + + +
+ + EGD203 SENNYBRIDGE + 520743N 0032924W -
520613N 0032645W -
520451N 0032532W -
520252N 0032804W -
520156N 0032943W -
520150N 0033139W -
515858N 0033729W -
515815N 0033935W -
515947N 0034105W -
520211N 0034019W -
520501N 0033532W -
520743N 0032924W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits:
Upper Limit: ALT 23000 Mon-Fri 0800-1800 (0700-1700).
Upper Limit: ALT 18000 Mon-Fri 1800-0800 (1700-0700), Fri 1800 (1700) - Mon 0800 (0700).

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01874-635599.

Remarks: SI 1974/1773.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.49,52.1286111111,7010.400000000001 -3.5922222222,52.08361111109999,7010.400000000001 -3.6719444444,52.03638888890001,7010.400000000001 -3.6847222222,51.9963888889,7010.400000000001 -3.659722222200001,51.97083333330001,7010.400000000001 -3.6247222222,51.9827777778,7010.400000000001 -3.5275,52.0305555556,7010.400000000001 -3.4952777778,52.0322222222,7010.400000000001 -3.4677777778,52.0477777778,7010.400000000001 -3.4255555556,52.08083333329999,7010.400000000001 -3.4458333333,52.1036111111,7010.400000000001 -3.49,52.1286111111,7010.400000000001 + + + + +
+ + EGD206 CARDINGTON + A circle, 1 NM radius, centred at 520621N 0002521W
Upper limit: 6000 FT MSL
Lower limit: SFC
Class: Activity: Balloons / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information: Cardington Met Office, Tel: 01234-744658, Mob: 07513-786573.

Danger Area Authority: MET Office.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4225,52.12247760369999,1828.8 -0.4264370798,52.1223001664,1828.8 -0.4302901553999999,52.1217716404,1828.8 -0.433977021,52.1209033022,1828.8 -0.437419028,52.1197136782,1828.8 -0.4405427677,52.1182281473,1828.8 -0.4432816393,52.1164783985,1828.8 -0.4455772722,52.1145017531,1828.8 -0.4473807689000001,52.11234036690001,1828.8 -0.4486537454,52.11004032899999,1828.8 -0.449369144,52.10765067820001,1828.8 -0.4495118043,52.1052223559,1828.8 -0.4490787784,52.1028071196,1828.8 -0.4480793863,52.10045643960001,1828.8 -0.4465350094000001,52.0982204027,1828.8 -0.4444786278,52.09614664570001,1828.8 -0.4419541121,52.0942793417,1828.8 -0.4390152849000001,52.09265826130001,1828.8 -0.4357247719,52.0913179268,1828.8 -0.4321526683,52.0902868787,1828.8 -0.4283750477,52.0895870705,1828.8 -0.4244723461,52.0892334015,1828.8 -0.4205276539,52.0892334015,1828.8 -0.4166249523000001,52.0895870705,1828.8 -0.4128473317,52.0902868787,1828.8 -0.4092752281,52.0913179268,1828.8 -0.4059847151,52.09265826130001,1828.8 -0.4030458879,52.0942793417,1828.8 -0.4005213722,52.09614664570001,1828.8 -0.3984649906,52.0982204027,1828.8 -0.3969206137,52.10045643960001,1828.8 -0.3959212216,52.1028071196,1828.8 -0.3954881957,52.1052223559,1828.8 -0.395630856,52.10765067820001,1828.8 -0.3963462546,52.11004032899999,1828.8 -0.3976192311,52.11234036690001,1828.8 -0.3994227277999999,52.1145017531,1828.8 -0.4017183606999999,52.1164783985,1828.8 -0.4044572323,52.1182281473,1828.8 -0.407580972,52.1197136782,1828.8 -0.411022979,52.1209033022,1828.8 -0.4147098446,52.1217716404,1828.8 -0.4185629202,52.1223001664,1828.8 -0.4225,52.12247760369999,1828.8 + + + + +
+ + EGD207 HOLBEACH + 524830N 0001200E -
525400N 0000633E thence clockwise by the arc of a circle radius 6.5 NM centred on 525000N 0001500E to
525300N 0002430E -
524830N 0002000E -
524830N 0001200E
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Holbeach Range on 122.750 MHz when open. SUAAIS: Holbeach Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Ops, Tel: 01406-550083. Booking: Range ATC, Tel: 01406-550364 Ext 7119.

Remarks: Airborne bookings and free-calling aircraft accepted subject to availability. Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Donna Nook and Pembrey AWRs. Ensure crossing clearance request is specific to Holbeach AWR. SI 1939/1608. UAS BVLOS will not be conducted above 18000 FT ALT (12000 FT ALT in the event of the activation of Contingency Airway T999).

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2,52.8083333333,7010.400000000001 0.3333333333,52.8083333333,7010.400000000001 0.4083333333,52.88333333329999,7010.400000000001 0.4035323371,52.888770376,7010.400000000001 0.3980704212,52.8939769833,7010.400000000001 0.3921256339,52.89898667170001,7010.400000000001 0.3857172013,52.9037831019,7010.400000000001 0.3788658825999999,52.9083506248,7010.400000000001 0.3715939029,52.91267433339999,7010.400000000001 0.3639248819000001,52.916740112,7010.400000000001 0.3558837567000001,52.9205346833,7010.400000000001 0.3474967008,52.9240456522,7010.400000000001 0.338791038,52.9272615471,7010.400000000001 0.3297951528,52.9301718581,7010.400000000001 0.3205383966,52.93276707209999,7010.400000000001 0.3110509909,52.9350387042,7010.400000000001 0.3013639265,52.9369793263,7010.400000000001 0.2915088612,52.9385825917,7010.400000000001 0.2815180137,52.9398432563,7010.400000000001 0.2714240568,52.9407571964,7010.400000000001 0.2612600077,52.941321422,7010.400000000001 0.2510591185,52.9415340873,7010.400000000001 0.2408547639,52.9413944965,7010.400000000001 0.2306803307,52.9409031063,7010.400000000001 0.2205691054,52.94006152430001,7010.400000000001 0.2105541631,52.93887250379999,7010.400000000001 0.2006682571,52.93733993410001,7010.400000000001 0.1909437092,52.9354688284,7010.400000000001 0.1814123023,52.933265306,7010.400000000001 0.1721051742,52.9307365725,7010.400000000001 0.1630527144,52.92789089589999,7010.400000000001 0.1542844628,52.9247375784,7010.400000000001 0.1458290125,52.92128692579999,7010.400000000001 0.1377139148,52.9175502132,7010.400000000001 0.1299655892,52.9135396473,7010.400000000001 0.1226092361,52.9092683259,7010.400000000001 0.1156687551,52.90475019460001,7010.400000000001 0.1091666667,52.9,7010.400000000001 0.2,52.8083333333,7010.400000000001 + + + + +
+ + EGD208 STANFORD + 523315N 0004050E -
523320N 0004500E -
523255N 0004800E -
523045N 0005000E -
522650N 0005050E -
522620N 0004830E -
522800N 0004500E -
522900N 0003900E -
523100N 0004000E -
523315N 0004050E
Upper limit: 7500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 7500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Lakenheath Zone on 128.900 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01842-855367.

Remarks: SI 1970/909 & SI 1975/24 (Amendment).

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6805555556,52.5541666667,2286 0.6666666667,52.51666666669999,2286 0.65,52.4833333333,2286 0.75,52.46666666670001,2286 0.8083333332999999,52.4388888889,2286 0.8472222221999999,52.4472222222,2286 0.8333333333000001,52.5125,2286 0.8,52.5486111111,2286 0.75,52.55555555559999,2286 0.6805555556,52.5541666667,2286 + + + + +
+ + EGD211 SWYNNERTON + A circle, 0.5 NM radius, centred at 525352N 0021312W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.22,52.9060987986,731.52 -2.2227704214,52.9059284347,731.52 -2.2254273585,52.9054243214,731.52 -2.2278619831,52.9046071082,731.52 -2.2299745875,52.9035102684,731.52 -2.2316786715,52.9021787258,731.52 -2.2329044861,52.9006670125,731.52 -2.2336018855,52.8990370336,731.52 -2.2337423743,52.89735552980001,731.52 -2.233320265,52.8956913442,731.52 -2.2323529,52.8941126028,731.52 -2.230879932,52.89268392709999,731.52 -2.2289616929,52.8914637897,731.52 -2.2266767188,52.8905021241,731.52 -2.2241185345,52.8898382828,731.52 -2.221391828,52.8894994296,731.52 -2.218608172,52.8894994296,731.52 -2.2158814655,52.8898382828,731.52 -2.2133232812,52.8905021241,731.52 -2.2110383071,52.8914637897,731.52 -2.209120068,52.89268392709999,731.52 -2.2076471,52.8941126028,731.52 -2.206679735,52.8956913442,731.52 -2.2062576257,52.89735552980001,731.52 -2.2063981145,52.8990370336,731.52 -2.2070955139,52.9006670125,731.52 -2.2083213285,52.9021787258,731.52 -2.2100254125,52.9035102684,731.52 -2.2121380169,52.9046071082,731.52 -2.2145726415,52.9054243214,731.52 -2.2172295786,52.9059284347,731.52 -2.22,52.9060987986,731.52 + + + + +
+ + EGD213 KINETON + A circle, 700 M radius, centred at 520902N 0012656W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Coventry Information on 123.830 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01869-257489.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4488888889,52.1568465441,731.52 -1.4512476826,52.1566769462,731.52 -1.4534792617,52.1561772992,731.52 -1.4554632808,52.1553745497,731.52 -1.45709276,52.1543119889,731.52 -1.4582798567,52.15304691579999,731.52 -1.4589606006,52.1516475448,731.52 -1.4590983369,52.15018932510001,731.52 -1.4586856924,52.1487508716,731.52 -1.4577449627,52.1474097263,731.52 -1.4563268989,52.14623817889999,731.52 -1.4545079643,52.14529937230001,731.52 -1.4523862089,52.1446439021,731.52 -1.4500759857,52.1443070918,731.52 -1.4477017921,52.1443070918,731.52 -1.4453915689,52.1446439021,731.52 -1.4432698135,52.14529937230001,731.52 -1.4414508789,52.14623817889999,731.52 -1.4400328151,52.1474097263,731.52 -1.4390920853,52.1487508716,731.52 -1.4386794409,52.15018932510001,731.52 -1.4388171771,52.1516475448,731.52 -1.4394979211,52.15304691579999,731.52 -1.4406850178,52.1543119889,731.52 -1.4423144969,52.1553745497,731.52 -1.4442985161,52.1561772992,731.52 -1.4465300952,52.1566769462,731.52 -1.4488888889,52.1568465441,731.52 + + + + +
+ + EGD215 NORTH LUFFENHAM + A circle, 610 M radius, centred at 523754N 0003557W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information: Guard Room, Tel: 01780-727644.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5991666667,52.63714836539999,731.52 -0.6014074807000001,52.6369761266,731.52 -0.6035074459999999,52.63647023659999,731.52 -0.6053345765,52.635662493,731.52 -0.6067740508,52.6346036641,731.52 -0.6077354312,52.6333602954,731.52 -0.6081583435,52.6320105244,731.52 -0.6080162628,52.6306391677,731.52 -0.6073181676,52.6293323909,731.52 -0.6061079637,52.6281722944,731.52 -0.6044617146,52.62723175719999,731.52 -0.6024828569,52.62656986109999,731.52 -0.600295702,52.62622818239999,731.52 -0.5980376314,52.62622818239999,731.52 -0.5958504764,52.62656986109999,731.52 -0.5938716187999999,52.62723175719999,731.52 -0.5922253696999999,52.6281722944,731.52 -0.5910151658,52.6293323909,731.52 -0.5903170706,52.6306391677,731.52 -0.5901749898,52.6320105244,731.52 -0.5905979021,52.6333602954,731.52 -0.5915592825,52.6346036641,731.52 -0.5929987568,52.635662493,731.52 -0.5948258873,52.63647023659999,731.52 -0.5969258527,52.6369761266,731.52 -0.5991666667,52.63714836539999,731.52 + + + + +
+ + EGD216 CREDENHILL + A circle, 2 NM radius, centred at 520453N 0024806W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2300 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 10,000 FT ALT by NOTAM.

Activity: Para Dropping / Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 124.750 MHz.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8016666667,52.1146775213,3048 -2.8072262898,52.1145009569,3048 -2.8127268489,52.1139731394,3048 -2.8181099118,52.113099676,3048 -2.8233183024,52.1118898454,3048 -2.828296712,52.1103564987,3048 -2.832992289499999,52.10851592179999,3048 -2.8373552052,52.1063876615,3048 -2.8413391811,52.10399431700001,3048 -2.8449019829,52.10136129840001,3048 -2.8480058678,52.0985165558,3048 -2.850617983499999,52.09549028130001,3048 -2.8527107142,52.0923145874,3048 -2.8542619706,52.089023165,3048 -2.8552554197,52.08565092560001,3048 -2.8556806534,52.0822336298,3048 -2.8555332935,52.0788075078,3048 -2.854815033,52.07540887529999,3048 -2.8535336121,52.07207374830001,3048 -2.851702731,52.0688374621,3048 -2.8493419001,52.0657342973,3048 -2.8464762284,52.0627971173,3048 -2.8431361539,52.0600570218,3048 -2.8393571186,52.0575430179,3048 -2.835179191,52.05528171489999,3048 -2.8306466414,52.0532970434,3048 -2.8258074726,52.0516100039,3048 -2.8207129137,52.05023844490001,3048 -2.8154168795,52.0491968762,3048 -2.8099754026,52.0484963154,3048 -2.8044460442,52.0481441727,3048 -2.7988872891,52.0481441727,3048 -2.7933579308,52.0484963154,3048 -2.7879164539,52.0491968762,3048 -2.7826204196,52.05023844490001,3048 -2.7775258607,52.0516100039,3048 -2.772686692,52.0532970434,3048 -2.7681541423,52.05528171489999,3048 -2.7639762147,52.0575430179,3048 -2.7601971794,52.0600570218,3048 -2.7568571049,52.0627971173,3048 -2.7539914332,52.0657342973,3048 -2.7516306023,52.0688374621,3048 -2.7497997213,52.07207374830001,3048 -2.7485183003,52.07540887529999,3048 -2.7478000398,52.0788075078,3048 -2.74765268,52.0822336298,3048 -2.7480779137,52.08565092560001,3048 -2.7490713628,52.089023165,3048 -2.7506226191,52.0923145874,3048 -2.7527153499,52.09549028130001,3048 -2.7553274655,52.0985165558,3048 -2.7584313504,52.10136129840001,3048 -2.7619941522,52.10399431700001,3048 -2.7659781281,52.1063876615,3048 -2.7703410438,52.10851592179999,3048 -2.7750366213,52.1103564987,3048 -2.7800150309,52.1118898454,3048 -2.7852234215,52.113099676,3048 -2.7906064844,52.1139731394,3048 -2.7961070436,52.1145009569,3048 -2.8016666667,52.1146775213,3048 + + + + +
+ + EGD217A LLANBEDR + 525022N 0040522W -
524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -
525022N 0040522W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + +
+ + EGD217B LLANBEDR + 525306N 0040947W -
525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -
525306N 0040947W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + +
+ + EGD217C LLANBEDR + 524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524603N 0040510W -
523933N 0041231W -
524222N 0041917W -
524942N 0041102W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 + + + + +
+ + EGD217D LLANBEDR + 524222N 0041917W -
523933N 0041231W -
523526N 0041712W -
523816N 0042359W -
524222N 0041917W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,1828.8 -4.3995916667,52.63763888889999,1828.8 -4.2867416667,52.5906805556,1828.8 -4.2084722222,52.6592083333,1828.8 -4.3215111111,52.70620277780001,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.3995916667,52.63763888889999,609.6 -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.3995916667,52.63763888889999,609.6 -4.3995916667,52.63763888889999,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3995916667,52.63763888889999,609.6 -4.2867416667,52.5906805556,609.6 -4.2867416667,52.5906805556,1828.8 -4.3995916667,52.63763888889999,1828.8 -4.3995916667,52.63763888889999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8 -4.2867416667,52.5906805556,1828.8 -4.2867416667,52.5906805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2084722222,52.6592083333,609.6 -4.3215111111,52.70620277780001,609.6 -4.3215111111,52.70620277780001,1828.8 -4.2084722222,52.6592083333,1828.8 -4.2084722222,52.6592083333,609.6 + + + + + +
+ + EGD217E LLANBEDR + 525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
524333N 0040503W -
525307N 0040530W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + +
+ + EGD217F LLANBEDR + 525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
525307N 0040530W -
525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
525028N 0040939W -
525306N 0040947W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + +
+ + EGD217G LLANBEDR + 525022N 0040522W -
524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -
525022N 0040522W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,1828.8 -4.0949801674,52.84151682579999,1828.8 -4.1007438086,52.8431637779,1828.8 -4.1067350168,52.8444800679,1828.8 -4.1129021488,52.8454543458,1828.8 -4.1191920321,52.84607821,1828.8 -4.1255504268,52.84634628049999,1828.8 -4.131922497,52.8462562454,1828.8 -4.1382532879,52.8458088811,1828.8 -4.1444882038,52.8450080457,1828.8 -4.1505734827,52.8438606453,1828.8 -4.1564566639,52.8423765741,1828.8 -4.1620870429,52.8405686282,1828.8 -4.1674161122,52.8384523943,1828.8 -4.1723979807,52.83604611490001,1828.8 -4.1769897708,52.8333705291,1828.8 -4.1811519882,52.8304486936,1828.8 -4.184848862,52.8273057818,1828.8 -4.188048651,52.8239688666,1828.8 -4.1907239156,52.82046668539999,1828.8 -4.1928517505,52.8168293921,1828.8 -4.1944139782,52.813088296,1828.8 -4.1953973017,52.8092755921,1828.8 -4.1957934135,52.8054240831,1828.8 -4.1955990621,52.8015668967,1828.8 -4.1948160749,52.7977372011,1828.8 -4.1934513366,52.79396791920001,1828.8 -4.1915167256,52.7902914462,1828.8 -4.189029006,52.7867393717,1828.8 -4.1860096801,52.783342209,1828.8 -4.1824847989,52.7801291336,1828.8 -4.1784847357,52.77712773390001,1828.8 -4.1740439228,52.77436377539999,1828.8 -4.169200554,52.77186098050001,1828.8 -4.1639962563,52.7696408264,1828.8 -4.1584757326,52.7677223618,1828.8 -4.1526863794,52.7661220445,1828.8 -4.1466778812,52.7648536015,1828.8 -4.1405017878,52.76392791199999,1828.8 -4.134211074,52.7633529149,1828.8 -4.1278596898,52.7631335411,1828.8 -4.1215021006,52.7632716721,1828.8 -4.115192825,52.7637661231,1828.8 -4.1089859706,52.764612654,1828.8 -4.1029347739,52.76580400480001,1828.8 -4.0970911477,52.76732995779999,1828.8 -4.0915052387,52.7691774242,1828.8 -4.086225,52.7713305556,1828.8 -4.0894944444,52.8395527778,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.0949801674,52.84151682579999,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1007438086,52.8431637779,1828.8 -4.0949801674,52.84151682579999,1828.8 -4.0949801674,52.84151682579999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1067350168,52.8444800679,1828.8 -4.1007438086,52.8431637779,1828.8 -4.1007438086,52.8431637779,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1129021488,52.8454543458,1828.8 -4.1067350168,52.8444800679,1828.8 -4.1067350168,52.8444800679,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1191920321,52.84607821,1828.8 -4.1129021488,52.8454543458,1828.8 -4.1129021488,52.8454543458,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.1255504268,52.84634628049999,1828.8 -4.1191920321,52.84607821,1828.8 -4.1191920321,52.84607821,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.131922497,52.8462562454,1828.8 -4.1255504268,52.84634628049999,1828.8 -4.1255504268,52.84634628049999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1382532879,52.8458088811,1828.8 -4.131922497,52.8462562454,1828.8 -4.131922497,52.8462562454,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1444882038,52.8450080457,1828.8 -4.1382532879,52.8458088811,1828.8 -4.1382532879,52.8458088811,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1505734827,52.8438606453,1828.8 -4.1444882038,52.8450080457,1828.8 -4.1444882038,52.8450080457,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1564566639,52.8423765741,1828.8 -4.1505734827,52.8438606453,1828.8 -4.1505734827,52.8438606453,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1620870429,52.8405686282,1828.8 -4.1564566639,52.8423765741,1828.8 -4.1564566639,52.8423765741,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1674161122,52.8384523943,1828.8 -4.1620870429,52.8405686282,1828.8 -4.1620870429,52.8405686282,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1723979807,52.83604611490001,1828.8 -4.1674161122,52.8384523943,1828.8 -4.1674161122,52.8384523943,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1769897708,52.8333705291,1828.8 -4.1723979807,52.83604611490001,1828.8 -4.1723979807,52.83604611490001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.1811519882,52.8304486936,1828.8 -4.1769897708,52.8333705291,1828.8 -4.1769897708,52.8333705291,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.184848862,52.8273057818,1828.8 -4.1811519882,52.8304486936,1828.8 -4.1811519882,52.8304486936,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.188048651,52.8239688666,1828.8 -4.184848862,52.8273057818,1828.8 -4.184848862,52.8273057818,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1907239156,52.82046668539999,1828.8 -4.188048651,52.8239688666,1828.8 -4.188048651,52.8239688666,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1928517505,52.8168293921,1828.8 -4.1907239156,52.82046668539999,1828.8 -4.1907239156,52.82046668539999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1944139782,52.813088296,1828.8 -4.1928517505,52.8168293921,1828.8 -4.1928517505,52.8168293921,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1953973017,52.8092755921,1828.8 -4.1944139782,52.813088296,1828.8 -4.1944139782,52.813088296,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1957934135,52.8054240831,1828.8 -4.1953973017,52.8092755921,1828.8 -4.1953973017,52.8092755921,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1955990621,52.8015668967,1828.8 -4.1957934135,52.8054240831,1828.8 -4.1957934135,52.8054240831,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1948160749,52.7977372011,1828.8 -4.1955990621,52.8015668967,1828.8 -4.1955990621,52.8015668967,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1934513366,52.79396791920001,1828.8 -4.1948160749,52.7977372011,1828.8 -4.1948160749,52.7977372011,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.1915167256,52.7902914462,1828.8 -4.1934513366,52.79396791920001,1828.8 -4.1934513366,52.79396791920001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.189029006,52.7867393717,1828.8 -4.1915167256,52.7902914462,1828.8 -4.1915167256,52.7902914462,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1860096801,52.783342209,1828.8 -4.189029006,52.7867393717,1828.8 -4.189029006,52.7867393717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1824847989,52.7801291336,1828.8 -4.1860096801,52.783342209,1828.8 -4.1860096801,52.783342209,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1784847357,52.77712773390001,1828.8 -4.1824847989,52.7801291336,1828.8 -4.1824847989,52.7801291336,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.1740439228,52.77436377539999,1828.8 -4.1784847357,52.77712773390001,1828.8 -4.1784847357,52.77712773390001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.169200554,52.77186098050001,1828.8 -4.1740439228,52.77436377539999,1828.8 -4.1740439228,52.77436377539999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1639962563,52.7696408264,1828.8 -4.169200554,52.77186098050001,1828.8 -4.169200554,52.77186098050001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1584757326,52.7677223618,1828.8 -4.1639962563,52.7696408264,1828.8 -4.1639962563,52.7696408264,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1526863794,52.7661220445,1828.8 -4.1584757326,52.7677223618,1828.8 -4.1584757326,52.7677223618,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1466778812,52.7648536015,1828.8 -4.1526863794,52.7661220445,1828.8 -4.1526863794,52.7661220445,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.1405017878,52.76392791199999,1828.8 -4.1466778812,52.7648536015,1828.8 -4.1466778812,52.7648536015,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.134211074,52.7633529149,1828.8 -4.1405017878,52.76392791199999,1828.8 -4.1405017878,52.76392791199999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1278596898,52.7631335411,1828.8 -4.134211074,52.7633529149,1828.8 -4.134211074,52.7633529149,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.1215021006,52.7632716721,1828.8 -4.1278596898,52.7631335411,1828.8 -4.1278596898,52.7631335411,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.115192825,52.7637661231,1828.8 -4.1215021006,52.7632716721,1828.8 -4.1215021006,52.7632716721,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1089859706,52.764612654,1828.8 -4.115192825,52.7637661231,1828.8 -4.115192825,52.7637661231,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.1029347739,52.76580400480001,1828.8 -4.1089859706,52.764612654,1828.8 -4.1089859706,52.764612654,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0970911477,52.76732995779999,1828.8 -4.1029347739,52.76580400480001,1828.8 -4.1029347739,52.76580400480001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.0915052387,52.7691774242,1828.8 -4.0970911477,52.76732995779999,1828.8 -4.0970911477,52.76732995779999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.0915052387,52.7691774242,1828.8 -4.0915052387,52.7691774242,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + +
+ + EGD217H LLANBEDR + 525306N 0040947W -
525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -
525306N 0040947W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,1828.8 -4.1716703219,52.88348920120001,1828.8 -4.1800610524,52.8815618217,1828.8 -4.1882253836,52.879307044,1828.8 -4.1961284314,52.8767345124,1828.8 -4.203736446,52.8738552286,1828.8 -4.2110169583,52.87068150359999,1828.8 -4.2179389192,52.8672269048,1828.8 -4.2244728329,52.8635061966,1828.8 -4.2305908832,52.8595352771,1828.8 -4.2362670523,52.8553311089,1828.8 -4.2414772309,52.8509116461,1828.8 -4.24619932,52.8462957566,1828.8 -4.2504133239,52.8415031405,1828.8 -4.2541014336,52.836554246,1828.8 -4.2572481003,52.8314701808,1828.8 -4.2598400991,52.82627262180001,1828.8 -4.2618665826,52.8209837219,1828.8 -4.2633191239,52.81562601520001,1828.8 -4.2641917489,52.8102223209,1828.8 -4.2644809586,52.8047956454,1828.8 -4.2641857397,52.79936908449999,1828.8 -4.263307566,52.7939657248,1828.8 -4.2618503879,52.78860854600001,1828.8 -4.2598206119,52.7833203228,1828.8 -4.2572270704,52.7781235288,1828.8 -4.2540809803,52.7730402409,1828.8 -4.2503958922,52.7680920465,1828.8 -4.2461876305,52.763299952,1828.8 -4.2414742231,52.7586842944,1828.8 -4.236275823,52.75426465569999,1828.8 -4.2306146206,52.7500597804,1828.8 -4.2245147485,52.7460874972,1828.8 -4.2180021779,52.7423646436,1828.8 -4.2111046078,52.7389069959,1828.8 -4.2038513475,52.735729203,1828.8 -4.1962731925,52.73284472500001,1828.8 -4.1884022946,52.7302657772,1828.8 -4.180272027,52.7280032789,1828.8 -4.1719168439,52.7260668081,1828.8 -4.1633721365,52.7244645613,1828.8 -4.1546740851,52.7232033196,1828.8 -4.1458595084,52.7222884205,1828.8 -4.1369657097,52.7217237352,1828.8 -4.1280303217,52.7215116532,1828.8 -4.1190911504,52.7216530717,1828.8 -4.1101860173,52.72214739249999,1828.8 -4.1013526024,52.7229925239,1828.8 -4.0926282873,52.7241848898,1828.8 -4.08405,52.72571944440001,1828.8 -4.086225,52.7713305556,1828.8 -4.0913879573,52.7692223853,1828.8 -4.0968429653,52.76740518580001,1828.8 -4.1025466245,52.76589502910001,1828.8 -4.1084520974,52.7647043103,1828.8 -4.1145109035,52.763842802,1828.8 -4.1206733141,52.763317574,1828.8 -4.1268887576,52.7631329367,1828.8 -4.1331062308,52.76329040510001,1828.8 -4.1392747141,52.76378868689999,1828.8 -4.1453435863,52.7646236933,1828.8 -4.1512630371,52.7657885717,1828.8 -4.1569844719,52.7672737619,1828.8 -4.1624609086,52.7690670735,1828.8 -4.1676473604,52.7711537858,1828.8 -4.1725012037,52.77351676720001,1828.8 -4.1769825268,52.77613661509999,1828.8 -4.1810544573,52.77899181389999,1828.8 -4.1846834655,52.7820589112,1828.8 -4.1878396407,52.7853127087,1828.8 -4.1904969392,52.7887264686,1828.8 -4.1926334009,52.7922721322,1828.8 -4.1942313326,52.7959205499,1828.8 -4.1952774577,52.79964171970001,1828.8 -4.1957630298,52.803405034,1828.8 -4.1956839083,52.8071795305,1828.8 -4.1950405983,52.8109341468,1828.8 -4.1938382505,52.8146379764,1828.8 -4.1920866238,52.818260523,1828.8 -4.1898000094,52.8217719521,1828.8 -4.1869971173,52.82514333729999,1828.8 -4.1837009258,52.8283468994,1828.8 -4.1799384954,52.8313562361,1828.8 -4.1757407482,52.8341465404,1828.8 -4.1711422147,52.8366948064,1828.8 -4.16618075,52.8389800201,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1630888889,52.8850805556,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1716703219,52.88348920120001,1828.8 -4.1630888889,52.8850805556,1828.8 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1800610524,52.8815618217,1828.8 -4.1716703219,52.88348920120001,1828.8 -4.1716703219,52.88348920120001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1882253836,52.879307044,1828.8 -4.1800610524,52.8815618217,1828.8 -4.1800610524,52.8815618217,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.1961284314,52.8767345124,1828.8 -4.1882253836,52.879307044,1828.8 -4.1882253836,52.879307044,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.203736446,52.8738552286,1828.8 -4.1961284314,52.8767345124,1828.8 -4.1961284314,52.8767345124,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2110169583,52.87068150359999,1828.8 -4.203736446,52.8738552286,1828.8 -4.203736446,52.8738552286,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2179389192,52.8672269048,1828.8 -4.2110169583,52.87068150359999,1828.8 -4.2110169583,52.87068150359999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2244728329,52.8635061966,1828.8 -4.2179389192,52.8672269048,1828.8 -4.2179389192,52.8672269048,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2305908832,52.8595352771,1828.8 -4.2244728329,52.8635061966,1828.8 -4.2244728329,52.8635061966,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2362670523,52.8553311089,1828.8 -4.2305908832,52.8595352771,1828.8 -4.2305908832,52.8595352771,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.2414772309,52.8509116461,1828.8 -4.2362670523,52.8553311089,1828.8 -4.2362670523,52.8553311089,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.24619932,52.8462957566,1828.8 -4.2414772309,52.8509116461,1828.8 -4.2414772309,52.8509116461,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2504133239,52.8415031405,1828.8 -4.24619932,52.8462957566,1828.8 -4.24619932,52.8462957566,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2541014336,52.836554246,1828.8 -4.2504133239,52.8415031405,1828.8 -4.2504133239,52.8415031405,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2572481003,52.8314701808,1828.8 -4.2541014336,52.836554246,1828.8 -4.2541014336,52.836554246,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2598400991,52.82627262180001,1828.8 -4.2572481003,52.8314701808,1828.8 -4.2572481003,52.8314701808,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2618665826,52.8209837219,1828.8 -4.2598400991,52.82627262180001,1828.8 -4.2598400991,52.82627262180001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2633191239,52.81562601520001,1828.8 -4.2618665826,52.8209837219,1828.8 -4.2618665826,52.8209837219,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2641917489,52.8102223209,1828.8 -4.2633191239,52.81562601520001,1828.8 -4.2633191239,52.81562601520001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2644809586,52.8047956454,1828.8 -4.2641917489,52.8102223209,1828.8 -4.2641917489,52.8102223209,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.2641857397,52.79936908449999,1828.8 -4.2644809586,52.8047956454,1828.8 -4.2644809586,52.8047956454,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.263307566,52.7939657248,1828.8 -4.2641857397,52.79936908449999,1828.8 -4.2641857397,52.79936908449999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2618503879,52.78860854600001,1828.8 -4.263307566,52.7939657248,1828.8 -4.263307566,52.7939657248,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2598206119,52.7833203228,1828.8 -4.2618503879,52.78860854600001,1828.8 -4.2618503879,52.78860854600001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2572270704,52.7781235288,1828.8 -4.2598206119,52.7833203228,1828.8 -4.2598206119,52.7833203228,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2540809803,52.7730402409,1828.8 -4.2572270704,52.7781235288,1828.8 -4.2572270704,52.7781235288,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2503958922,52.7680920465,1828.8 -4.2540809803,52.7730402409,1828.8 -4.2540809803,52.7730402409,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2461876305,52.763299952,1828.8 -4.2503958922,52.7680920465,1828.8 -4.2503958922,52.7680920465,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.2414742231,52.7586842944,1828.8 -4.2461876305,52.763299952,1828.8 -4.2461876305,52.763299952,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.236275823,52.75426465569999,1828.8 -4.2414742231,52.7586842944,1828.8 -4.2414742231,52.7586842944,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2306146206,52.7500597804,1828.8 -4.236275823,52.75426465569999,1828.8 -4.236275823,52.75426465569999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2245147485,52.7460874972,1828.8 -4.2306146206,52.7500597804,1828.8 -4.2306146206,52.7500597804,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2180021779,52.7423646436,1828.8 -4.2245147485,52.7460874972,1828.8 -4.2245147485,52.7460874972,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2111046078,52.7389069959,1828.8 -4.2180021779,52.7423646436,1828.8 -4.2180021779,52.7423646436,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.2038513475,52.735729203,1828.8 -4.2111046078,52.7389069959,1828.8 -4.2111046078,52.7389069959,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1962731925,52.73284472500001,1828.8 -4.2038513475,52.735729203,1828.8 -4.2038513475,52.735729203,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.1884022946,52.7302657772,1828.8 -4.1962731925,52.73284472500001,1828.8 -4.1962731925,52.73284472500001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.180272027,52.7280032789,1828.8 -4.1884022946,52.7302657772,1828.8 -4.1884022946,52.7302657772,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1719168439,52.7260668081,1828.8 -4.180272027,52.7280032789,1828.8 -4.180272027,52.7280032789,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1633721365,52.7244645613,1828.8 -4.1719168439,52.7260668081,1828.8 -4.1719168439,52.7260668081,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1546740851,52.7232033196,1828.8 -4.1633721365,52.7244645613,1828.8 -4.1633721365,52.7244645613,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1458595084,52.7222884205,1828.8 -4.1546740851,52.7232033196,1828.8 -4.1546740851,52.7232033196,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1369657097,52.7217237352,1828.8 -4.1458595084,52.7222884205,1828.8 -4.1458595084,52.7222884205,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1280303217,52.7215116532,1828.8 -4.1369657097,52.7217237352,1828.8 -4.1369657097,52.7217237352,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1190911504,52.7216530717,1828.8 -4.1280303217,52.7215116532,1828.8 -4.1280303217,52.7215116532,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1101860173,52.72214739249999,1828.8 -4.1190911504,52.7216530717,1828.8 -4.1190911504,52.7216530717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.1013526024,52.7229925239,1828.8 -4.1101860173,52.72214739249999,1828.8 -4.1101860173,52.72214739249999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.0926282873,52.7241848898,1828.8 -4.1013526024,52.7229925239,1828.8 -4.1013526024,52.7229925239,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.08405,52.72571944440001,1828.8 -4.0926282873,52.7241848898,1828.8 -4.0926282873,52.7241848898,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.08405,52.72571944440001,1828.8 -4.08405,52.72571944440001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0913879573,52.7692223853,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.0968429653,52.76740518580001,1828.8 -4.0913879573,52.7692223853,1828.8 -4.0913879573,52.7692223853,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1025466245,52.76589502910001,1828.8 -4.0968429653,52.76740518580001,1828.8 -4.0968429653,52.76740518580001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1084520974,52.7647043103,1828.8 -4.1025466245,52.76589502910001,1828.8 -4.1025466245,52.76589502910001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1145109035,52.763842802,1828.8 -4.1084520974,52.7647043103,1828.8 -4.1084520974,52.7647043103,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1206733141,52.763317574,1828.8 -4.1145109035,52.763842802,1828.8 -4.1145109035,52.763842802,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1268887576,52.7631329367,1828.8 -4.1206733141,52.763317574,1828.8 -4.1206733141,52.763317574,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1331062308,52.76329040510001,1828.8 -4.1268887576,52.7631329367,1828.8 -4.1268887576,52.7631329367,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1392747141,52.76378868689999,1828.8 -4.1331062308,52.76329040510001,1828.8 -4.1331062308,52.76329040510001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1453435863,52.7646236933,1828.8 -4.1392747141,52.76378868689999,1828.8 -4.1392747141,52.76378868689999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1512630371,52.7657885717,1828.8 -4.1453435863,52.7646236933,1828.8 -4.1453435863,52.7646236933,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1569844719,52.7672737619,1828.8 -4.1512630371,52.7657885717,1828.8 -4.1512630371,52.7657885717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1624609086,52.7690670735,1828.8 -4.1569844719,52.7672737619,1828.8 -4.1569844719,52.7672737619,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1676473604,52.7711537858,1828.8 -4.1624609086,52.7690670735,1828.8 -4.1624609086,52.7690670735,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1725012037,52.77351676720001,1828.8 -4.1676473604,52.7711537858,1828.8 -4.1676473604,52.7711537858,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1769825268,52.77613661509999,1828.8 -4.1725012037,52.77351676720001,1828.8 -4.1725012037,52.77351676720001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1810544573,52.77899181389999,1828.8 -4.1769825268,52.77613661509999,1828.8 -4.1769825268,52.77613661509999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1846834655,52.7820589112,1828.8 -4.1810544573,52.77899181389999,1828.8 -4.1810544573,52.77899181389999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1878396407,52.7853127087,1828.8 -4.1846834655,52.7820589112,1828.8 -4.1846834655,52.7820589112,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1904969392,52.7887264686,1828.8 -4.1878396407,52.7853127087,1828.8 -4.1878396407,52.7853127087,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1926334009,52.7922721322,1828.8 -4.1904969392,52.7887264686,1828.8 -4.1904969392,52.7887264686,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1942313326,52.7959205499,1828.8 -4.1926334009,52.7922721322,1828.8 -4.1926334009,52.7922721322,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1952774577,52.79964171970001,1828.8 -4.1942313326,52.7959205499,1828.8 -4.1942313326,52.7959205499,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1957630298,52.803405034,1828.8 -4.1952774577,52.79964171970001,1828.8 -4.1952774577,52.79964171970001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1956839083,52.8071795305,1828.8 -4.1957630298,52.803405034,1828.8 -4.1957630298,52.803405034,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1950405983,52.8109341468,1828.8 -4.1956839083,52.8071795305,1828.8 -4.1956839083,52.8071795305,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1938382505,52.8146379764,1828.8 -4.1950405983,52.8109341468,1828.8 -4.1950405983,52.8109341468,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1920866238,52.818260523,1828.8 -4.1938382505,52.8146379764,1828.8 -4.1938382505,52.8146379764,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1898000094,52.8217719521,1828.8 -4.1920866238,52.818260523,1828.8 -4.1920866238,52.818260523,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1869971173,52.82514333729999,1828.8 -4.1898000094,52.8217719521,1828.8 -4.1898000094,52.8217719521,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1837009258,52.8283468994,1828.8 -4.1869971173,52.82514333729999,1828.8 -4.1869971173,52.82514333729999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1799384954,52.8313562361,1828.8 -4.1837009258,52.8283468994,1828.8 -4.1837009258,52.8283468994,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1757407482,52.8341465404,1828.8 -4.1799384954,52.8313562361,1828.8 -4.1799384954,52.8313562361,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.1711422147,52.8366948064,1828.8 -4.1757407482,52.8341465404,1828.8 -4.1757407482,52.8341465404,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.16618075,52.8389800201,1828.8 -4.1711422147,52.8366948064,1828.8 -4.1711422147,52.8366948064,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8 -4.16618075,52.8389800201,1828.8 -4.16618075,52.8389800201,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1608972222,52.8409833333,609.6 + + + + + +
+ + EGD217I LLANBEDR + 524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524603N 0040510W -
523933N 0041231W -
524222N 0041917W -
524942N 0041102W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.2084722222,52.6592083333,1828.8 -4.0860444444,52.7675166667,1828.8 -4.086225,52.7713305556,1828.8 -4.0913798344,52.76921870109999,1828.8 -4.0968320407,52.7674020804,1828.8 -4.1025326866,52.76589215620001,1828.8 -4.1084350162,52.76470130689999,1828.8 -4.1144906333,52.76383929410001,1828.8 -4.1206498956,52.7633131834,1828.8 -4.1268623184,52.76312728700001,1828.8 -4.1330769853,52.7632831285,1828.8 -4.1392429612,52.7637794307,1828.8 -4.145309707,52.7646121256,1828.8 -4.1512274901,52.7657743881,1828.8 -4.1569477885,52.7672566908,1828.8 -4.1624236863,52.7690468821,1828.8 -4.167610256,52.7711302844,1828.8 -4.1724649246,52.7734898141,1828.8 -4.1769478222,52.7761061204,1828.8 -4.1810221083,52.7789577431,1828.8 -4.1846542748,52.7820212872,1828.8 -4.1878144214,52.7852716143,1828.8 -4.1904765038,52.7886820476,1828.8 -4.1926185491,52.7922245896,1828.8 -4.1942228402,52.7958701517,1828.8 -4.1952760644,52.799588792,1828.8 -4.1957694276,52.8033499607,1828.8 -4.1956987304,52.8071227506,1828.8 -4.195064408,52.81087615129999,1828.8 -4.193871531,52.8145793036,1828.8 -4.1921297686,52.81820175400001,1828.8 -4.1898533133,52.8217137049,1828.8 -4.1870607687,52.82508626089999,1828.8 -4.183775,52.8282916667,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.3215111111,52.70620277780001,1828.8 -4.183775,52.8282916667,1828.8 -4.183775,52.8282916667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.0860444444,52.7675166667,1828.8 -4.2084722222,52.6592083333,1828.8 -4.2084722222,52.6592083333,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.0860444444,52.7675166667,1828.8 -4.0860444444,52.7675166667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0913798344,52.76921870109999,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.0968320407,52.7674020804,1828.8 -4.0913798344,52.76921870109999,1828.8 -4.0913798344,52.76921870109999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1025326866,52.76589215620001,1828.8 -4.0968320407,52.7674020804,1828.8 -4.0968320407,52.7674020804,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1084350162,52.76470130689999,1828.8 -4.1025326866,52.76589215620001,1828.8 -4.1025326866,52.76589215620001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1144906333,52.76383929410001,1828.8 -4.1084350162,52.76470130689999,1828.8 -4.1084350162,52.76470130689999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1206498956,52.7633131834,1828.8 -4.1144906333,52.76383929410001,1828.8 -4.1144906333,52.76383929410001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1268623184,52.76312728700001,1828.8 -4.1206498956,52.7633131834,1828.8 -4.1206498956,52.7633131834,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1330769853,52.7632831285,1828.8 -4.1268623184,52.76312728700001,1828.8 -4.1268623184,52.76312728700001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.1392429612,52.7637794307,1828.8 -4.1330769853,52.7632831285,1828.8 -4.1330769853,52.7632831285,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.145309707,52.7646121256,1828.8 -4.1392429612,52.7637794307,1828.8 -4.1392429612,52.7637794307,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1512274901,52.7657743881,1828.8 -4.145309707,52.7646121256,1828.8 -4.145309707,52.7646121256,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1569477885,52.7672566908,1828.8 -4.1512274901,52.7657743881,1828.8 -4.1512274901,52.7657743881,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.1624236863,52.7690468821,1828.8 -4.1569477885,52.7672566908,1828.8 -4.1569477885,52.7672566908,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.167610256,52.7711302844,1828.8 -4.1624236863,52.7690468821,1828.8 -4.1624236863,52.7690468821,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1724649246,52.7734898141,1828.8 -4.167610256,52.7711302844,1828.8 -4.167610256,52.7711302844,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1769478222,52.7761061204,1828.8 -4.1724649246,52.7734898141,1828.8 -4.1724649246,52.7734898141,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1810221083,52.7789577431,1828.8 -4.1769478222,52.7761061204,1828.8 -4.1769478222,52.7761061204,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1846542748,52.7820212872,1828.8 -4.1810221083,52.7789577431,1828.8 -4.1810221083,52.7789577431,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1878144214,52.7852716143,1828.8 -4.1846542748,52.7820212872,1828.8 -4.1846542748,52.7820212872,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1904765038,52.7886820476,1828.8 -4.1878144214,52.7852716143,1828.8 -4.1878144214,52.7852716143,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1926185491,52.7922245896,1828.8 -4.1904765038,52.7886820476,1828.8 -4.1904765038,52.7886820476,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1942228402,52.7958701517,1828.8 -4.1926185491,52.7922245896,1828.8 -4.1926185491,52.7922245896,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1952760644,52.799588792,1828.8 -4.1942228402,52.7958701517,1828.8 -4.1942228402,52.7958701517,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1957694276,52.8033499607,1828.8 -4.1952760644,52.799588792,1828.8 -4.1952760644,52.799588792,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.1956987304,52.8071227506,1828.8 -4.1957694276,52.8033499607,1828.8 -4.1957694276,52.8033499607,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.195064408,52.81087615129999,1828.8 -4.1956987304,52.8071227506,1828.8 -4.1956987304,52.8071227506,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.193871531,52.8145793036,1828.8 -4.195064408,52.81087615129999,1828.8 -4.195064408,52.81087615129999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1921297686,52.81820175400001,1828.8 -4.193871531,52.8145793036,1828.8 -4.193871531,52.8145793036,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1898533133,52.8217137049,1828.8 -4.1921297686,52.81820175400001,1828.8 -4.1921297686,52.81820175400001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.1870607687,52.82508626089999,1828.8 -4.1898533133,52.8217137049,1828.8 -4.1898533133,52.8217137049,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 -4.183775,52.8282916667,1828.8 -4.1870607687,52.82508626089999,1828.8 -4.1870607687,52.82508626089999,609.6 + + + + + +
+ + EGD217J LLANBEDR + 525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
524333N 0040503W -
525307N 0040530W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,1828.8 -4.08405,52.72571944440001,1828.8 -4.0755987733,52.7276026422,1828.8 -4.0673688901,52.7298184726,1828.8 -4.0593953848,52.7323568761,1828.8 -4.0517125112,52.7352069624,1828.8 -4.0443532948,52.738356502,1828.8 -4.037349392,52.7417919777,1828.8 -4.030730955,52.7454986418,1828.8 -4.0245265029,52.7494605784,1828.8 -4.0187627984,52.7536607714,1828.8 -4.0134647331,52.75808117619999,1828.8 -4.0086552188,52.7627027967,1828.8 -4.0043550877,52.7675057658,1828.8 -4.0005830012,52.7724694303,1828.8 -3.9973553675,52.7775724392,1828.8 -3.9946862679,52.78279283410001,1828.8 -3.9925873936,52.7881081439,1828.8 -3.9910679921,52.79349548079999,1828.8 -3.9901348241,52.7989316381,1828.8 -3.989792130500001,52.80439319039999,1828.8 -3.9900416104,52.8098565941,1828.8 -3.990882410299999,52.8152982887,1828.8 -3.9923111235,52.8206947986,1828.8 -3.9943218012,52.8260228348,1828.8 -3.9969059746,52.831259395,1828.8 -4.0000526878,52.8363818638,1828.8 -4.0037485419,52.8413681109,1828.8 -4.0079777498,52.8461965867,1828.8 -4.0127222017,52.85084641669999,1828.8 -4.0179615407,52.8552974922,1828.8 -4.0236732496,52.8595305579,1828.8 -4.0298327457,52.8635272962,1828.8 -4.0364134868,52.8672704074,1828.8 -4.0433870849,52.8707436851,1828.8 -4.0507234291,52.8739320877,1828.8 -4.0583908159,52.8768218039,1828.8 -4.0663560872,52.8794003139,1828.8 -4.0745847751,52.8816564439,1828.8 -4.0830412523,52.8835804155,1828.8 -4.0916888889,52.8851638889,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.08405,52.72571944440001,1828.8 -4.0916888889,52.8851638889,1828.8 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0755987733,52.7276026422,1828.8 -4.08405,52.72571944440001,1828.8 -4.08405,52.72571944440001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0673688901,52.7298184726,1828.8 -4.0755987733,52.7276026422,1828.8 -4.0755987733,52.7276026422,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0593953848,52.7323568761,1828.8 -4.0673688901,52.7298184726,1828.8 -4.0673688901,52.7298184726,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0517125112,52.7352069624,1828.8 -4.0593953848,52.7323568761,1828.8 -4.0593953848,52.7323568761,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.0443532948,52.738356502,1828.8 -4.0517125112,52.7352069624,1828.8 -4.0517125112,52.7352069624,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.037349392,52.7417919777,1828.8 -4.0443532948,52.738356502,1828.8 -4.0443532948,52.738356502,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.030730955,52.7454986418,1828.8 -4.037349392,52.7417919777,1828.8 -4.037349392,52.7417919777,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0245265029,52.7494605784,1828.8 -4.030730955,52.7454986418,1828.8 -4.030730955,52.7454986418,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0187627984,52.7536607714,1828.8 -4.0245265029,52.7494605784,1828.8 -4.0245265029,52.7494605784,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0134647331,52.75808117619999,1828.8 -4.0187627984,52.7536607714,1828.8 -4.0187627984,52.7536607714,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0086552188,52.7627027967,1828.8 -4.0134647331,52.75808117619999,1828.8 -4.0134647331,52.75808117619999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0043550877,52.7675057658,1828.8 -4.0086552188,52.7627027967,1828.8 -4.0086552188,52.7627027967,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -4.0005830012,52.7724694303,1828.8 -4.0043550877,52.7675057658,1828.8 -4.0043550877,52.7675057658,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9973553675,52.7775724392,1828.8 -4.0005830012,52.7724694303,1828.8 -4.0005830012,52.7724694303,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9946862679,52.78279283410001,1828.8 -3.9973553675,52.7775724392,1828.8 -3.9973553675,52.7775724392,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9925873936,52.7881081439,1828.8 -3.9946862679,52.78279283410001,1828.8 -3.9946862679,52.78279283410001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9910679921,52.79349548079999,1828.8 -3.9925873936,52.7881081439,1828.8 -3.9925873936,52.7881081439,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.9901348241,52.7989316381,1828.8 -3.9910679921,52.79349548079999,1828.8 -3.9910679921,52.79349548079999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.989792130500001,52.80439319039999,1828.8 -3.9901348241,52.7989316381,1828.8 -3.9901348241,52.7989316381,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.9900416104,52.8098565941,1828.8 -3.989792130500001,52.80439319039999,1828.8 -3.989792130500001,52.80439319039999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.990882410299999,52.8152982887,1828.8 -3.9900416104,52.8098565941,1828.8 -3.9900416104,52.8098565941,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9923111235,52.8206947986,1828.8 -3.990882410299999,52.8152982887,1828.8 -3.990882410299999,52.8152982887,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9943218012,52.8260228348,1828.8 -3.9923111235,52.8206947986,1828.8 -3.9923111235,52.8206947986,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -3.9969059746,52.831259395,1828.8 -3.9943218012,52.8260228348,1828.8 -3.9943218012,52.8260228348,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0000526878,52.8363818638,1828.8 -3.9969059746,52.831259395,1828.8 -3.9969059746,52.831259395,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0037485419,52.8413681109,1828.8 -4.0000526878,52.8363818638,1828.8 -4.0000526878,52.8363818638,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0079777498,52.8461965867,1828.8 -4.0037485419,52.8413681109,1828.8 -4.0037485419,52.8413681109,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0127222017,52.85084641669999,1828.8 -4.0079777498,52.8461965867,1828.8 -4.0079777498,52.8461965867,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0179615407,52.8552974922,1828.8 -4.0127222017,52.85084641669999,1828.8 -4.0127222017,52.85084641669999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0236732496,52.8595305579,1828.8 -4.0179615407,52.8552974922,1828.8 -4.0179615407,52.8552974922,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0298327457,52.8635272962,1828.8 -4.0236732496,52.8595305579,1828.8 -4.0236732496,52.8595305579,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0364134868,52.8672704074,1828.8 -4.0298327457,52.8635272962,1828.8 -4.0298327457,52.8635272962,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0433870849,52.8707436851,1828.8 -4.0364134868,52.8672704074,1828.8 -4.0364134868,52.8672704074,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0507234291,52.8739320877,1828.8 -4.0433870849,52.8707436851,1828.8 -4.0433870849,52.8707436851,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0583908159,52.8768218039,1828.8 -4.0507234291,52.8739320877,1828.8 -4.0507234291,52.8739320877,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0663560872,52.8794003139,1828.8 -4.0583908159,52.8768218039,1828.8 -4.0583908159,52.8768218039,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0745847751,52.8816564439,1828.8 -4.0663560872,52.8794003139,1828.8 -4.0663560872,52.8794003139,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0830412523,52.8835804155,1828.8 -4.0745847751,52.8816564439,1828.8 -4.0745847751,52.8816564439,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8 -4.0830412523,52.8835804155,1828.8 -4.0830412523,52.8835804155,609.6 + + + + + +
+ + EGD217K LLANBEDR + 525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
525307N 0040530W -
525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
525028N 0040939W -
525306N 0040947W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1553132526,52.8426949429,1828.8 -4.149494417,52.8440909498,1828.8 -4.143489638,52.8451603374,1828.8 -4.1373488445,52.8458942118,1828.8 -4.131123106,52.84628646940001,1828.8 -4.1248642045,52.8463338475,1828.8 -4.1186242003,52.8460359521,1828.8 -4.1124549952,52.8453952609,1828.8 -4.1064078968,52.8444171027,1828.8 -4.100533189,52.8431096128,1828.8 -4.0948797102,52.8414836643,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0916888889,52.8851638889,1828.8 -4.1004821132,52.88639803100001,1828.8 -4.1093902725,52.8872810751,1828.8 -4.118375237,52.8878082526,1828.8 -4.1273981205,52.88797728189999,1828.8 -4.13641987,52.8877874313,1828.8 -4.1454014374,52.88723952270001,1828.8 -4.1543039514,52.8863359272,1828.8 -4.1630888889,52.8850805556,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8 -4.1630888889,52.8850805556,1828.8 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.1553132526,52.8426949429,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1608972222,52.8409833333,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.149494417,52.8440909498,1828.8 -4.1553132526,52.8426949429,1828.8 -4.1553132526,52.8426949429,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.143489638,52.8451603374,1828.8 -4.149494417,52.8440909498,1828.8 -4.149494417,52.8440909498,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.1373488445,52.8458942118,1828.8 -4.143489638,52.8451603374,1828.8 -4.143489638,52.8451603374,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.131123106,52.84628646940001,1828.8 -4.1373488445,52.8458942118,1828.8 -4.1373488445,52.8458942118,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1248642045,52.8463338475,1828.8 -4.131123106,52.84628646940001,1828.8 -4.131123106,52.84628646940001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1186242003,52.8460359521,1828.8 -4.1248642045,52.8463338475,1828.8 -4.1248642045,52.8463338475,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1124549952,52.8453952609,1828.8 -4.1186242003,52.8460359521,1828.8 -4.1186242003,52.8460359521,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.1064078968,52.8444171027,1828.8 -4.1124549952,52.8453952609,1828.8 -4.1124549952,52.8453952609,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.100533189,52.8431096128,1828.8 -4.1064078968,52.8444171027,1828.8 -4.1064078968,52.8444171027,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0948797102,52.8414836643,1828.8 -4.100533189,52.8431096128,1828.8 -4.100533189,52.8431096128,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8 -4.0948797102,52.8414836643,1828.8 -4.0948797102,52.8414836643,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1004821132,52.88639803100001,1828.8 -4.0916888889,52.8851638889,1828.8 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.1093902725,52.8872810751,1828.8 -4.1004821132,52.88639803100001,1828.8 -4.1004821132,52.88639803100001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.118375237,52.8878082526,1828.8 -4.1093902725,52.8872810751,1828.8 -4.1093902725,52.8872810751,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.1273981205,52.88797728189999,1828.8 -4.118375237,52.8878082526,1828.8 -4.118375237,52.8878082526,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.13641987,52.8877874313,1828.8 -4.1273981205,52.88797728189999,1828.8 -4.1273981205,52.88797728189999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1454014374,52.88723952270001,1828.8 -4.13641987,52.8877874313,1828.8 -4.13641987,52.8877874313,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1543039514,52.8863359272,1828.8 -4.1454014374,52.88723952270001,1828.8 -4.1454014374,52.88723952270001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8 -4.1543039514,52.8863359272,1828.8 -4.1543039514,52.8863359272,609.6 + + + + + +
+ + EGD218A FAIRFORD + 514815N 0013543W -
514016N 0013518W -
513958N 0014917W -
514110N 0015928W -
514744N 0015952W -
514815N 0013543W
Upper limit: FL75
Lower limit: SFC
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Brize Radar on 124.275 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5951848611,51.80407725,2286 -1.9976505556,51.79551097220001,2286 -1.9911186944,51.6860482222,2286 -1.8215250833,51.6661864444,2286 -1.58842725,51.6709806111,2286 -1.5951848611,51.80407725,2286 + + + + +
+ + EGD218B FAIRFORD + 520518N 0020404W -
514803N 0014539W -
514749N 0015601W -
514901N 0020407W -
515342N 0022132W -
520518N 0020404W
Upper limit: FL240
Lower limit: FL50
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Below FL160 Brize Radar on 124.275 MHz. At/above FL160 Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,7315.199999999999 -2.3588221389,51.8948650833,7315.199999999999 -2.0686747222,51.8169415833,7315.199999999999 -1.9337063889,51.79696427779999,7315.199999999999 -1.76084275,51.8007185,7315.199999999999 -2.0679103333,52.0883218333,7315.199999999999 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,1524 -2.3588221389,51.8948650833,1524 -2.0686747222,51.8169415833,1524 -1.9337063889,51.79696427779999,1524 -1.76084275,51.8007185,1524 -2.0679103333,52.0883218333,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,1524 -2.3588221389,51.8948650833,1524 -2.3588221389,51.8948650833,7315.199999999999 -2.0679103333,52.0883218333,7315.199999999999 -2.0679103333,52.0883218333,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.3588221389,51.8948650833,1524 -2.0686747222,51.8169415833,1524 -2.0686747222,51.8169415833,7315.199999999999 -2.3588221389,51.8948650833,7315.199999999999 -2.3588221389,51.8948650833,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.0686747222,51.8169415833,1524 -1.9337063889,51.79696427779999,1524 -1.9337063889,51.79696427779999,7315.199999999999 -2.0686747222,51.8169415833,7315.199999999999 -2.0686747222,51.8169415833,1524 + + + + + + relativeToGround + + + relativeToGround + + -1.9337063889,51.79696427779999,1524 -1.76084275,51.8007185,1524 -1.76084275,51.8007185,7315.199999999999 -1.9337063889,51.79696427779999,7315.199999999999 -1.9337063889,51.79696427779999,1524 + + + + + + relativeToGround + + + relativeToGround + + -1.76084275,51.8007185,1524 -2.0679103333,52.0883218333,1524 -2.0679103333,52.0883218333,7315.199999999999 -1.76084275,51.8007185,7315.199999999999 -1.76084275,51.8007185,1524 + + + + + +
+ + EGD218C FAIRFORD + 521533N 0021510W -
520518N 0020404W -
515342N 0022132W -
515701N 0023402W -
520117N 0023842W -
521533N 0021510W
Upper limit: FL660
Lower limit: FL160
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.567252,51.9502352778,20116.8 -2.3588221389,51.8948650833,20116.8 -2.0679103333,52.0883218333,20116.8 -2.2526999167,52.25927605559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,4876.8 -2.6449074167,52.02142933329999,4876.8 -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.25927605559999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,4876.8 -2.6449074167,52.02142933329999,4876.8 -2.6449074167,52.02142933329999,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.2526999167,52.25927605559999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.6449074167,52.02142933329999,4876.8 -2.567252,51.9502352778,4876.8 -2.567252,51.9502352778,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.6449074167,52.02142933329999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.3588221389,51.8948650833,20116.8 -2.567252,51.9502352778,20116.8 -2.567252,51.9502352778,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.0679103333,52.0883218333,20116.8 -2.3588221389,51.8948650833,20116.8 -2.3588221389,51.8948650833,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.25927605559999,4876.8 -2.2526999167,52.25927605559999,20116.8 -2.0679103333,52.0883218333,20116.8 -2.0679103333,52.0883218333,4876.8 + + + + + +
+ + EGD218D FAIRFORD + 523258N 0023414W -
521533N 0021510W -
520117N 0023842W -
521342N 0025221W -
522607N 0025118W -
523258N 0023414W
Upper limit: FL660
Lower limit: FL200
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8724085833,52.2284006944,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.5705153611,52.5495711667,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,6096 -2.8549897222,52.4352228333,6096 -2.8724085833,52.2284006944,6096 -2.6449074167,52.02142933329999,6096 -2.2526999167,52.25927605559999,6096 -2.5705153611,52.5495711667,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,6096 -2.8549897222,52.4352228333,6096 -2.8549897222,52.4352228333,20116.8 -2.5705153611,52.5495711667,20116.8 -2.5705153611,52.5495711667,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.8549897222,52.4352228333,6096 -2.8724085833,52.2284006944,6096 -2.8724085833,52.2284006944,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8549897222,52.4352228333,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.8724085833,52.2284006944,6096 -2.6449074167,52.02142933329999,6096 -2.6449074167,52.02142933329999,20116.8 -2.8724085833,52.2284006944,20116.8 -2.8724085833,52.2284006944,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.6449074167,52.02142933329999,6096 -2.2526999167,52.25927605559999,6096 -2.2526999167,52.25927605559999,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.6449074167,52.02142933329999,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,6096 -2.5705153611,52.5495711667,6096 -2.5705153611,52.5495711667,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.2526999167,52.25927605559999,6096 + + + + + +
+ + EGD304 UPPER HULME + A circle, 1.5 NM radius, centred at 530951N 0015730W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Manchester APP on 118.580 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.

Remarks: SI 1985/1082.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9583333333,53.1891285695,1066.8 -1.9632487194,53.1889532633,1066.8 -1.9680949854,53.1884298098,1066.8 -1.9728039882,53.1875655697,1066.8 -1.9773095245,53.1863726948,1066.8 -1.9815482657,53.1848679569,1066.8 -1.9854606515,53.1830725106,1066.8 -1.9889917292,53.1810115942,1066.8 -1.9920919267,53.1787141743,1066.8 -1.994717749,53.1762125364,1066.8 -1.9968323868,53.1735418303,1066.8 -1.9984062307,53.1707395745,1066.8 -1.9994172825,53.1678451281,1066.8 -1.9998514587,53.1648991371,1066.8 -1.9997027821,53.1619429631,1066.8 -1.9989734591,53.15901810199999,1066.8 -1.9976738419,53.15616560210001,1066.8 -1.995822277,53.1534254881,1066.8 -1.9934448418,53.1508362003,1066.8 -1.990574974,53.14843405639999,1066.8 -1.9872529981,53.14625274370001,1066.8 -1.983525558,53.1443228474,1066.8 -1.9794449609,53.1426714238,1066.8 -1.9750684446,53.1413216224,1066.8 -1.9704573761,53.1402923625,1066.8 -1.9656763943,53.13959806939999,1066.8 -1.9607925076,53.1392484733,1066.8 -1.9558741591,53.1392484733,1066.8 -1.9509902724,53.13959806939999,1066.8 -1.9462092906,53.1402923625,1066.8 -1.9415982221,53.1413216224,1066.8 -1.9372217058,53.1426714238,1066.8 -1.9331411087,53.1443228474,1066.8 -1.9294136686,53.14625274370001,1066.8 -1.9260916927,53.14843405639999,1066.8 -1.9232218248,53.1508362003,1066.8 -1.9208443897,53.1534254881,1066.8 -1.9189928248,53.15616560210001,1066.8 -1.9176932075,53.15901810199999,1066.8 -1.9169638845,53.1619429631,1066.8 -1.916815208,53.1648991371,1066.8 -1.9172493842,53.1678451281,1066.8 -1.918260436,53.1707395745,1066.8 -1.9198342799,53.1735418303,1066.8 -1.9219489177,53.1762125364,1066.8 -1.9245747399,53.1787141743,1066.8 -1.9276749375,53.1810115942,1066.8 -1.9312060152,53.1830725106,1066.8 -1.935118401,53.1848679569,1066.8 -1.9393571422,53.1863726948,1066.8 -1.9438626785,53.1875655697,1066.8 -1.9485716812,53.1884298098,1066.8 -1.9534179472,53.1889532633,1066.8 -1.9583333333,53.1891285695,1066.8 + + + + +
+ + EGD305 BECKINGHAM + 530554N 0004134W -
530542N 0004034W -
530427N 0004044W -
530428N 0004205W -
530534N 0004217W -
530554N 0004134W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 07769-730481.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6927777778,53.0983333333,457.2 -0.7047222222,53.0927777778,457.2 -0.7013888889,53.0744444444,457.2 -0.6788888889,53.07416666669999,457.2 -0.6761111111,53.09499999999999,457.2 -0.6927777778,53.0983333333,457.2 + + + + +
+ + EGD307 DONNA NOOK + 532331N 0001354E -
532932N 0000503E thence clockwise by the arc of a circle radius 5 NM centred on 532830N 0001315E to -
532331N 0001354E
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 20,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Donna Nook Range on 122.750 MHz when open. SUAAIS: Donna Nook Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01507-359126.

Remarks: Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Holbeach and Pembrey AWRs. Ensure crossing clearance request is specific to Donna Nook AWR. SI 1939/451. UAS BVLOS will not be conducted above 12,000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2316666667,53.3919444444,7010.400000000001 0.2406825788,53.39252947290001,7010.400000000001 0.2496135246,53.3934738632,7010.400000000001 0.2584233162,53.3947627808,7010.400000000001 0.2670748532,53.3963907993,7010.400000000001 0.2755316902,53.398351064,7010.400000000001 0.283758188,53.4006353204,7010.400000000001 0.2917196616,53.4032339479,7010.400000000001 0.299382525,53.4061360005,7010.400000000001 0.3067144306,53.40932925129999,7010.400000000001 0.3136844052,53.4128002441,7010.400000000001 0.3202629797,53.41653434860001,7010.400000000001 0.3264223132,53.4205158216,7010.400000000001 0.3321363105,53.4247278727,7010.400000000001 0.3373807333,53.4291527337,7010.400000000001 0.3421333029,53.43377173329999,7010.400000000001 0.3463737964,53.4385653748,7010.400000000001 0.3500841336,53.4435134178,7010.400000000001 0.353248456,53.44859496269999,7010.400000000001 0.3558531958999999,53.45378853859999,7010.400000000001 0.3578871374000001,53.4590721933,7010.400000000001 0.3593414664,53.4644235858,7010.400000000001 0.3602098119,53.4698200802,7010.400000000001 0.3604882759999999,53.47523884140001,7010.400000000001 0.3601754547,53.4806569311,7010.400000000001 0.3592724472,53.4860514054,7010.400000000001 0.3577828553,53.4913994117,7010.400000000001 0.3557127719000001,53.4966782858,7010.400000000001 0.3530707586999999,53.501865648,7010.400000000001 0.3498678134,53.5069394986,7010.400000000001 0.3461173266,53.5118783116,7010.400000000001 0.3418350278,53.5166611264,7010.400000000001 0.3370389214,53.5212676377,7010.400000000001 0.3317492124,53.5256782822,7010.400000000001 0.3259882231,53.5298743225,7010.400000000001 0.3197802995,53.5338379274,7010.400000000001 0.313151709,53.5375522487,7010.400000000001 0.3061305297,53.5410014936,7010.400000000001 0.2987465312,53.54417099270001,7010.400000000001 0.2910310476,53.5470472631,7010.400000000001 0.2830168442,53.5496180668,7010.400000000001 0.2747379765,53.5518724632,7010.400000000001 0.2662296443,53.5538008569,7010.400000000001 0.2575280401,53.55539503859999,7010.400000000001 0.2486701928,53.556648221,7010.400000000001 0.2396938079,53.5575550683,7010.400000000001 0.2306371044,53.5581117187,7010.400000000001 0.2215386491,53.5583158018,7010.400000000001 0.2124371901,53.5581664484,7010.400000000001 0.2033714882,53.5576642946,7010.400000000001 0.1943801493,53.5568114788,7010.400000000001 0.1855014572,53.5556116326,7010.400000000001 0.1767732078,53.554069865,7010.400000000001 0.1682325452,53.5521927402,7010.400000000001 0.1599158018,53.54998824919999,7010.400000000001 0.1518583412,53.54746577560001,7010.400000000001 0.144094406,53.5446360542,7010.400000000001 0.1366569705,53.5415111256,7010.400000000001 0.1295775996,53.5381042833,7010.400000000001 0.1228863138,53.5344300172,7010.400000000001 0.116611461,53.5305039502,7010.400000000001 0.1107795966,53.52634277189999,7010.400000000001 0.1054153713,53.52196416590001,7010.400000000001 0.1005414271,53.51738673450001,7010.400000000001 0.0961783027,53.5126299184,7010.400000000001 0.09234434850000001,53.5077139136,7010.400000000001 0.08905565090000001,53.5026595851,7010.400000000001 0.0863259664,53.4974883771,7010.400000000001 0.0841666667,53.4922222222,7010.400000000001 0.2316666667,53.3919444444,7010.400000000001 + + + + +
+ + EGD314 HARPUR HILL + A circle, 0.5 NM radius, centred at 531343N 0015528W
Upper limit: 2900 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Manchester APP on 118.580 MHz.

Contact: HSE (The Health and Safety Executive), Tel: 0203-028 2000.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9244444444,53.2369316665,883.9200000000001 -1.9272361795,53.2367613117,883.9200000000001 -1.9299135563,53.2362572255,883.9200000000001 -1.932366909,53.2354400564,883.9200000000001 -1.9344957623,53.2343432761,883.9200000000001 -1.9362129508,53.23301180599999,883.9200000000001 -1.9374481891,53.2315001758,883.9200000000001 -1.9381509465,53.2298702871,883.9200000000001 -1.9382925095,53.2281888772,883.9200000000001 -1.9378671475,53.2265247852,883.9200000000001 -1.9368923376,53.2249461335,883.9200000000001 -1.9354080383,53.2235175393,883.9200000000001 -1.9334750457,53.2222974722,883.9200000000001 -1.9311725002,53.2213358622,883.9200000000001 -1.9285946453,53.2206720594,883.9200000000001 -1.9258469737,53.2203332259,883.9200000000001 -1.9230419152,53.2203332259,883.9200000000001 -1.9202942436,53.2206720594,883.9200000000001 -1.9177163887,53.2213358622,883.9200000000001 -1.9154138432,53.2222974722,883.9200000000001 -1.9134808506,53.2235175393,883.9200000000001 -1.9119965513,53.2249461335,883.9200000000001 -1.9110217413,53.2265247852,883.9200000000001 -1.9105963794,53.2281888772,883.9200000000001 -1.9107379424,53.2298702871,883.9200000000001 -1.9114406998,53.2315001758,883.9200000000001 -1.9126759381,53.23301180599999,883.9200000000001 -1.9143931266,53.2343432761,883.9200000000001 -1.9165219799,53.2354400564,883.9200000000001 -1.9189753326,53.2362572255,883.9200000000001 -1.9216527094,53.2367613117,883.9200000000001 -1.9244444444,53.2369316665,883.9200000000001 + + + + +
+ + EGD323A SOUTHERN COMPLEX + 551710N 0001428E -
550143N 0011753E -
543102N 0003132W -
544841N 0005456W -
545744N 0005457W -
551710N 0001428E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,1524 -0.9158333333000001,54.96233333329999,1524 -0.9156,54.8112972222,1524 -0.5256138889,54.5171138889,1524 1.298075,55.0285222222,1524 0.2412277778,55.2861722222,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,1524 -0.9158333333000001,54.96233333329999,1524 -0.9158333333000001,54.96233333329999,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,1524 -0.9156,54.8112972222,1524 -0.9156,54.8112972222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9158333333000001,54.96233333329999,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,1524 -0.5256138889,54.5171138889,1524 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,1524 1.298075,55.0285222222,1524 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 0.2412277778,55.2861722222,1524 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524 + + + + + +
+ + EGD323B SOUTHERN COMPLEX + 550143N 0011753E -
545059N 0020010E -
541451N 0001028W -
543102N 0003132W -
550143N 0011753E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 -0.5256138889,54.5171138889,1524 -0.1744611111,54.24745,1524 2.0026916667,54.8496888889,1524 1.298075,55.0285222222,1524 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 -0.5256138889,54.5171138889,1524 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,1524 -0.1744611111,54.24745,1524 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,1524 2.0026916667,54.8496888889,1524 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 1.298075,55.0285222222,1524 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524 + + + + + +
+ + EGD323C SOUTHERN COMPLEX + 545059N 0020010E -
544532N 0022109E -
540644N 0000002W -
541451N 0001028W -
545059N 0020010E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -0.0005361111,54.11218055559999,20116.8 2.3526361111,54.75875000000001,20116.8 2.0026916667,54.8496888889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 -0.1744611111,54.24745,1524 -0.0005361111,54.11218055559999,1524 2.3526361111,54.75875000000001,1524 2.0026916667,54.8496888889,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 -0.1744611111,54.24745,1524 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,1524 -0.0005361111,54.11218055559999,1524 -0.0005361111,54.11218055559999,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,1524 2.3526361111,54.75875000000001,1524 2.3526361111,54.75875000000001,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 2.0026916667,54.8496888889,1524 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,1524 + + + + + +
+ + EGD323D SOUTHERN COMPLEX + 544532N 0022109E -
543948N 0024252E -
543143N 0025434E -
541738N 0030110E -
533813N 0003557E -
540644N 0000002W -
544532N 0022109E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,20116.8 -0.0005361111,54.11218055559999,20116.8 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875000000001,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 -0.0005361111,54.11218055559999,1524 0.599175,53.6369388889,1524 3.0193416667,54.2940166667,1524 2.9095444444,54.5285361111,1524 2.7144361111,54.6632333333,1524 2.3526361111,54.75875000000001,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 -0.0005361111,54.11218055559999,1524 -0.0005361111,54.11218055559999,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,1524 0.599175,53.6369388889,1524 0.599175,53.6369388889,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,1524 3.0193416667,54.2940166667,1524 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 2.9095444444,54.5285361111,1524 2.9095444444,54.5285361111,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.9095444444,54.5285361111,1524 2.7144361111,54.6632333333,1524 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.7144361111,54.6632333333,1524 2.3526361111,54.75875000000001,1524 2.3526361111,54.75875000000001,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,1524 + + + + + +
+ + EGD323E SOUTHERN COMPLEX + 541738N 0030110E -
541733N 0030112E -
535535N 0025714E -
532807N 0024241E -
533813N 0003557E -
541738N 0030110E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 2.7113888889,53.4686111111,20116.8 2.9538888889,53.92638888889999,20116.8 3.0200138889,54.29257222219999,20116.8 3.0193416667,54.2940166667,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 0.599175,53.6369388889,1524 2.7113888889,53.4686111111,1524 2.9538888889,53.92638888889999,1524 3.0200138889,54.29257222219999,1524 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 0.599175,53.6369388889,1524 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,1524 2.7113888889,53.4686111111,1524 2.7113888889,53.4686111111,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.7113888889,53.4686111111,1524 2.9538888889,53.92638888889999,1524 2.9538888889,53.92638888889999,20116.8 2.7113888889,53.4686111111,20116.8 2.7113888889,53.4686111111,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.9538888889,53.92638888889999,1524 3.0200138889,54.29257222219999,1524 3.0200138889,54.29257222219999,20116.8 2.9538888889,53.92638888889999,20116.8 2.9538888889,53.92638888889999,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0200138889,54.29257222219999,1524 3.0193416667,54.2940166667,1524 3.0193416667,54.2940166667,20116.8 3.0200138889,54.29257222219999,20116.8 3.0200138889,54.29257222219999,1524 + + + + + +
+ + EGD323F SOUTHERN COMPLEX + 545744N 0005457W -
544841N 0005456W -
542402N 0005518W -
544229N 0011251W -
545210N 0010815W -
545513N 0010343W -
545744N 0005457W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,20116.8 -1.0619444444,54.9202777778,20116.8 -1.1375,54.8694444444,20116.8 -1.2140305556,54.7081583333,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9156,54.8112972222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,4572 -1.0619444444,54.9202777778,4572 -1.1375,54.8694444444,4572 -1.2140305556,54.7081583333,4572 -0.9216388889,54.40066111109999,4572 -0.9156,54.8112972222,4572 -0.9158333333000001,54.96233333329999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,4572 -1.0619444444,54.9202777778,4572 -1.0619444444,54.9202777778,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9158333333000001,54.96233333329999,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.0619444444,54.9202777778,4572 -1.1375,54.8694444444,4572 -1.1375,54.8694444444,20116.8 -1.0619444444,54.9202777778,20116.8 -1.0619444444,54.9202777778,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.1375,54.8694444444,4572 -1.2140305556,54.7081583333,4572 -1.2140305556,54.7081583333,20116.8 -1.1375,54.8694444444,20116.8 -1.1375,54.8694444444,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.2140305556,54.7081583333,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -1.2140305556,54.7081583333,20116.8 -1.2140305556,54.7081583333,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.9156,54.8112972222,4572 -0.9156,54.8112972222,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9158333333000001,54.96233333329999,4572 -0.9158333333000001,54.96233333329999,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572 + + + + + +
+ + EGD323G SOUTHERN COMPLEX + 544841N 0005456W -
543102N 0003132W -
542402N 0005518W -
544841N 0005456W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9216388889,54.40066111109999,4572 -0.5256138889,54.5171138889,4572 -0.9156,54.8112972222,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.5256138889,54.5171138889,4572 -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9156,54.8112972222,4572 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572 + + + + + +
+ + EGD323H SOUTHERN COMPLEX + 543102N 0003132W -
541451N 0001028W -
540726N 0003547W -
542402N 0005518W -
543102N 0003132W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9216388889,54.40066111109999,4572 -0.5964777778,54.1240138889,4572 -0.1744611111,54.24745,4572 -0.5256138889,54.5171138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.5964777778,54.1240138889,4572 -0.5964777778,54.1240138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5964777778,54.1240138889,4572 -0.1744611111,54.24745,4572 -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5256138889,54.5171138889,4572 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572 + + + + + +
+ + EGD323J SOUTHERN COMPLEX + 541451N 0001028W -
540644N 0000002W -
535908N 0002606W -
540726N 0003547W -
541451N 0001028W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.4349,53.9855666667,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.1744611111,54.24745,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5964777778,54.1240138889,4572 -0.4349,53.9855666667,4572 -0.0005361111,54.11218055559999,4572 -0.1744611111,54.24745,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5964777778,54.1240138889,4572 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5964777778,54.1240138889,4572 -0.4349,53.9855666667,4572 -0.4349,53.9855666667,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.4349,53.9855666667,4572 -0.0005361111,54.11218055559999,4572 -0.0005361111,54.11218055559999,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.1744611111,54.24745,4572 -0.1744611111,54.24745,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,4572 + + + + + +
+ + EGD323K SOUTHERN COMPLEX + 540644N 0000002W -
533813N 0003557E -
534331N 0000805W -
535908N 0002606W -
540644N 0000002W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,20116.8 -0.4349,53.9855666667,20116.8 -0.1348055556,53.7253805556,20116.8 0.599175,53.6369388889,20116.8 -0.0005361111,54.11218055559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.4349,53.9855666667,4572 -0.1348055556,53.7253805556,4572 0.599175,53.6369388889,4572 -0.0005361111,54.11218055559999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.4349,53.9855666667,4572 -0.4349,53.9855666667,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.4349,53.9855666667,4572 -0.1348055556,53.7253805556,4572 -0.1348055556,53.7253805556,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1348055556,53.7253805556,4572 0.599175,53.6369388889,4572 0.599175,53.6369388889,20116.8 -0.1348055556,53.7253805556,20116.8 -0.1348055556,53.7253805556,4572 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,4572 -0.0005361111,54.11218055559999,4572 -0.0005361111,54.11218055559999,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,4572 + + + + + +
+ + EGD323L SOUTHERN COMPLEX + 552430N 0004952E -
550944N 0014759E -
550143N 0011753E -
551710N 0001428E -
552430N 0004952E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,20116.8 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 0.2412277778,55.2861722222,3048 1.298075,55.0285222222,3048 1.7996194444,55.1621805556,3048 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 0.2412277778,55.2861722222,3048 0.2412277778,55.2861722222,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,3048 1.298075,55.0285222222,3048 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 0.8311305556,55.4081972222,3048 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + +
+ + EGD323M SOUTHERN COMPLEX + 550944N 0014759E -
545840N 0022938E -
545059N 0020010E -
550143N 0011753E -
550944N 0014759E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.4938992222,54.97779488889999,20116.8 1.7996194444,55.1621805556,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 1.298075,55.0285222222,3048 2.0026916667,54.8496888889,3048 2.4938992222,54.97779488889999,3048 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 1.298075,55.0285222222,3048 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,3048 2.0026916667,54.8496888889,3048 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + +
+ + EGD323N SOUTHERN COMPLEX + 545840N 0022938E -
544951N 0023752E -
544532N 0022109E -
545059N 0020010E -
545840N 0022938E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,20116.8 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875000000001,20116.8 2.6309753889,54.8308915833,20116.8 2.4938992222,54.97779488889999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.0026916667,54.8496888889,3048 2.3526361111,54.75875000000001,3048 2.6309753889,54.8308915833,3048 2.4938992222,54.97779488889999,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.0026916667,54.8496888889,3048 2.0026916667,54.8496888889,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,3048 2.3526361111,54.75875000000001,3048 2.3526361111,54.75875000000001,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,3048 2.6309753889,54.8308915833,3048 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048 + + + + + +
+ + EGD323P SOUTHERN COMPLEX + 544951N 0023752E -
543143N 0025434E -
543948N 0024252E -
544532N 0022109E -
544951N 0023752E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875000000001,20116.8 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.6309753889,54.8308915833,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.3526361111,54.75875000000001,3048 2.7144361111,54.6632333333,3048 2.9095444444,54.5285361111,3048 2.6309753889,54.8308915833,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.3526361111,54.75875000000001,3048 2.3526361111,54.75875000000001,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,3048 2.7144361111,54.6632333333,3048 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.7144361111,54.6632333333,3048 2.9095444444,54.5285361111,3048 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.9095444444,54.5285361111,3048 2.6309753889,54.8308915833,3048 2.6309753889,54.8308915833,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,3048 + + + + + +
+ + EGD323Q SOUTHERN COMPLEX + 553347N 0013625E -
553150N 0015622E -
551616N 0021300E -
550944N 0014759E -
552430N 0004952E -
553347N 0013625E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,20116.8 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 1.9394305556,55.5305138889,20116.8 1.6068611111,55.5631527778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,3048 0.8311305556,55.4081972222,3048 1.7996194444,55.1621805556,3048 2.2167416667,55.2711027778,3048 1.9394305556,55.5305138889,3048 1.6068611111,55.5631527778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,3048 0.8311305556,55.4081972222,3048 0.8311305556,55.4081972222,20116.8 1.6068611111,55.5631527778,20116.8 1.6068611111,55.5631527778,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 2.2167416667,55.2711027778,3048 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.9394305556,55.5305138889,3048 1.9394305556,55.5305138889,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.9394305556,55.5305138889,3048 1.6068611111,55.5631527778,3048 1.6068611111,55.5631527778,20116.8 1.9394305556,55.5305138889,20116.8 1.9394305556,55.5305138889,3048 + + + + + +
+ + EGD323R SOUTHERN COMPLEX + 551616N 0021300E -
545840N 0022938E -
550944N 0014759E -
551616N 0021300E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 2.4938992222,54.97779488889999,20116.8 2.2167416667,55.2711027778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.7996194444,55.1621805556,3048 2.4938992222,54.97779488889999,3048 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.2167416667,55.2711027778,3048 2.2167416667,55.2711027778,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + +
+ + EGD324A WADDINGTON LOW + A circle, 5 NM radius, centred at 530958N 0003126W
Upper limit: FL105
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.

Contact: Waddington ATC, Tel: 01522-727451/727452.

Remarks: High energy manoeuvres related to display flying training only.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5238888889,53.24931701730001,3200.4 -0.5329620222,53.2491385233,3200.4 -0.5419960775,53.24860381020001,3200.4 -0.5509521479,53.24771518070001,3200.4 -0.5597916681,53.2464764618,3200.4 -0.5684765836,53.24489298790001,3200.4 -0.5769695164,53.2429715769,3200.4 -0.5852339289,53.2407205011,3200.4 -0.5932342833000001,53.23814945079999,3200.4 -0.6009361957,53.2352694915,3200.4 -0.6083065862,53.2320930161,3200.4 -0.6153138218,53.2286336905,3200.4 -0.6219278531,53.2249063941,3200.4 -0.6281203442,53.2209271548,3200.4 -0.6338647934,53.21671307940001,3200.4 -0.6391366472,53.2122822792,3200.4 -0.6439134041,53.2076537911,3200.4 -0.6481747101000001,53.20284749500001,3200.4 -0.6519024438,53.197884028,3200.4 -0.6550807917,53.19278469469999,3200.4 -0.6576963139000001,53.1875713753,3200.4 -0.6597379981,53.18226643100001,3200.4 -0.6611973038,53.1768926078,3200.4 -0.6620681955,53.17147293869999,3200.4 -0.6623471645,53.1660306441,3200.4 -0.6620332407,53.1605890328,3200.4 -0.6611279923,53.1551714022,3200.4 -0.6596355158,53.1498009378,3200.4 -0.6575624144,53.144500615,3200.4 -0.6549177658999999,53.1392931008,3200.4 -0.651713081,53.13420065700001,3200.4 -0.6479622505,53.129245046,3200.4 -0.6436814828,53.124447438,3200.4 -0.6388892324,53.1198283214,3200.4 -0.6336061185,53.11540741570001,3200.4 -0.6278548351,53.1112035887,3200.4 -0.6216600529,53.10723477610001,3200.4 -0.6150483124,53.1035179065,3200.4 -0.6080479107,53.1000688292,3200.4 -0.6006887801,53.09690224840001,3200.4 -0.5930023609,53.0940316606,3200.4 -0.5850214681,53.0914692984,3200.4 -0.5767801523,53.0892260788,3200.4 -0.5683135565,53.0873115574,3200.4 -0.5596577674,53.0857338887,3200.4 -0.5508496647,53.0844997914,3200.4 -0.5419267654,53.0836145207,3200.4 -0.5329270671,53.0830818461,3200.4 -0.5238888889,53.0829040355,3200.4 -0.5148507107,53.0830818461,3200.4 -0.5058510124,53.0836145207,3200.4 -0.4969281131,53.0844997914,3200.4 -0.4881200103,53.0857338887,3200.4 -0.4794642213,53.0873115574,3200.4 -0.4709976254000001,53.0892260788,3200.4 -0.4627563097,53.0914692984,3200.4 -0.4547754169,53.0940316606,3200.4 -0.4470889977,53.09690224840001,3200.4 -0.4397298670999999,53.1000688292,3200.4 -0.4327294654,53.1035179065,3200.4 -0.4261177249,53.10723477610001,3200.4 -0.4199229426,53.1112035887,3200.4 -0.4141716593,53.11540741570001,3200.4 -0.4088885453,53.1198283214,3200.4 -0.4040962949,53.124447438,3200.4 -0.3998155273,53.129245046,3200.4 -0.3960646967,53.13420065700001,3200.4 -0.3928600119,53.1392931008,3200.4 -0.3902153634000001,53.144500615,3200.4 -0.3881422619,53.1498009378,3200.4 -0.3866497854,53.1551714022,3200.4 -0.3857445371,53.1605890328,3200.4 -0.3854306133000001,53.1660306441,3200.4 -0.3857095823,53.17147293869999,3200.4 -0.386580474,53.1768926078,3200.4 -0.3880397797,53.18226643100001,3200.4 -0.3900814637999999,53.1875713753,3200.4 -0.3926969860000001,53.19278469469999,3200.4 -0.395875334,53.197884028,3200.4 -0.3996030676,53.20284749500001,3200.4 -0.4038643737,53.2076537911,3200.4 -0.4086411306,53.2122822792,3200.4 -0.4139129844,53.21671307940001,3200.4 -0.4196574336,53.2209271548,3200.4 -0.4258499247,53.2249063941,3200.4 -0.432463956,53.2286336905,3200.4 -0.4394711915999999,53.2320930161,3200.4 -0.4468415821,53.2352694915,3200.4 -0.4545434945,53.23814945079999,3200.4 -0.4625438488,53.2407205011,3200.4 -0.4708082614,53.2429715769,3200.4 -0.4793011942,53.24489298790001,3200.4 -0.4879861096000001,53.2464764618,3200.4 -0.4968256299,53.24771518070001,3200.4 -0.5057817003,53.24860381020001,3200.4 -0.5148157555,53.2491385233,3200.4 -0.5238888889,53.24931701730001,3200.4 + + + + +
+ + EGD324B WADDINGTON MEDIUM + 531343N 0004324W -
530818N 0001452W -
525556N 0002123W -
530120N 0004950W -
531343N 0004324W
Upper limit: FL195
Lower limit: FL105
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.

Contact: Waddington ATC, Tel: 01522-727451/727452.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,5943.6 -0.8306333333000001,53.0220944444,5943.6 -0.3564722222,52.93216944440001,5943.6 -0.247825,53.1383611111,5943.6 -0.7233333333,53.2286111111,5943.6 + + + + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,3200.4 -0.8306333333000001,53.0220944444,3200.4 -0.3564722222,52.93216944440001,3200.4 -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,3200.4 -0.8306333333000001,53.0220944444,3200.4 -0.8306333333000001,53.0220944444,5943.6 -0.7233333333,53.2286111111,5943.6 -0.7233333333,53.2286111111,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.8306333333000001,53.0220944444,3200.4 -0.3564722222,52.93216944440001,3200.4 -0.3564722222,52.93216944440001,5943.6 -0.8306333333000001,53.0220944444,5943.6 -0.8306333333000001,53.0220944444,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.3564722222,52.93216944440001,3200.4 -0.247825,53.1383611111,3200.4 -0.247825,53.1383611111,5943.6 -0.3564722222,52.93216944440001,5943.6 -0.3564722222,52.93216944440001,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 -0.7233333333,53.2286111111,5943.6 -0.247825,53.1383611111,5943.6 -0.247825,53.1383611111,3200.4 + + + + + +
+ + EGD401 BALLYKINLER + 541334N 0054612W -
541256N 0054734W -
541316N 0055038W -
541440N 0054940W - then along the river to
541526N 0055010W -
541525N 0054718W -
541334N 0054612W
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 02844-610392.

Remarks: SI 1940/756.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.77,54.2261111111,975.36 -5.7883333333,54.25694444440001,975.36 -5.8361111111,54.25722222219999,975.36 -5.835386111100001,54.2552055556,975.36 -5.828741666699999,54.2502138889,975.36 -5.8250583333,54.2466888889,975.36 -5.825505555600001,54.2453583333,975.36 -5.8277777778,54.2444444444,975.36 -5.8438888889,54.2211111111,975.36 -5.7927777778,54.2155555556,975.36 -5.77,54.2261111111,975.36 + + + + +
+ + EGD402A LUCE BAY (N) + 550332N 0050509W -
545600N 0045800W -
545600N 0044744W -
544650N 0043837W -
545008N 0044939W -
545100N 0044946W -
545217N 0045134W -
545208N 0045404W -
544953N 0045653W -
544541N 0045627W -
544215N 0045339W -
544007N 0045032W -
543915N 0044653W -
543815N 0045352W -
545812N 0051210W -
550218N 0050909W -
550332N 0050509W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0858333333,55.0588888889,7010.400000000001 -5.1525,55.0383333333,7010.400000000001 -5.2027777778,54.97,7010.400000000001 -4.8977777778,54.63750000000001,7010.400000000001 -4.7813888889,54.6541666667,7010.400000000001 -4.8422222222,54.6686111111,7010.400000000001 -4.8941666667,54.7041666667,7010.400000000001 -4.9408333333,54.7613888889,7010.400000000001 -4.9480555556,54.8313888889,7010.400000000001 -4.9011111111,54.8688888889,7010.400000000001 -4.8594444444,54.8713888889,7010.400000000001 -4.8294444444,54.85,7010.400000000001 -4.8275,54.83555555560001,7010.400000000001 -4.6436111111,54.7805555556,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + +
+ + EGD402B LUCE BAY (N) + 550332N 0050509W -
550254N 0045410W -
545600N 0044744W -
545600N 0045800W -
550332N 0050509W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0858333333,55.0588888889,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9027777778,55.0483333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + +
+ + EGD402C LUCE BAY (N) + A circle, 3000 FT radius, centred at 545659N 0045752W
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9644444444,54.9579361819,1219.2 -4.9673177437,54.9577680078,1219.2 -4.9700733403,54.9572703748,1219.2 -4.9725983613,54.9564636675,1219.2 -4.9747893947,54.9553809299,1219.2 -4.9765567285,54.9540665095,1219.2 -4.9778280257,54.9525742383,1219.2 -4.9785512828,54.95096522630001,1219.2 -4.9786969516,54.9493053564,1219.2 -4.9782591389,54.94766258589999,1219.2 -4.9772558366,54.9461041639,1219.2 -4.9757281738,54.9446938793,1219.2 -4.9737387244,54.9434894509,1219.2 -4.9713689403,54.942540168,1219.2 -4.968715816,54.9418848754,1219.2 -4.9658879218,54.94155038609999,1219.2 -4.963000967,54.94155038609999,1219.2 -4.9601730729,54.9418848754,1219.2 -4.9575199486,54.942540168,1219.2 -4.9551501645,54.9434894509,1219.2 -4.9531607151,54.9446938793,1219.2 -4.9516330523,54.9461041639,1219.2 -4.95062975,54.94766258589999,1219.2 -4.9501919373,54.9493053564,1219.2 -4.9503376061,54.95096522630001,1219.2 -4.9510608631,54.9525742383,1219.2 -4.9523321604,54.9540665095,1219.2 -4.9540994942,54.9553809299,1219.2 -4.9562905276,54.9564636675,1219.2 -4.9588155486,54.9572703748,1219.2 -4.9615711452,54.9577680078,1219.2 -4.9644444444,54.9579361819,1219.2 + + + + +
+ + EGD403A LUCE BAY + 545141N 0045438W -
545139N 0045041W -
545100N 0044946W -
544850N 0045646W -
544953N 0045653W -
545141N 0045438W
Upper limit: 3000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9105555556,54.8613888889,914.4000000000001 -4.9480555556,54.8313888889,914.4000000000001 -4.9461111111,54.8138888889,914.4000000000001 -4.8294444444,54.85,914.4000000000001 -4.8447222222,54.8608333333,914.4000000000001 -4.9105555556,54.8613888889,914.4000000000001 + + + + +
+ + EGD403B LUCE BAY + 545208N 0045404W -
545217N 0045134W -
545100N 0044946W -
545008N 0044939W -
544650N 0043837W -
544304N 0043500W -
544050N 0043543W -
543915N 0044653W -
544007N 0045032W -
544215N 0045339W -
544541N 0045627W -
544953N 0045653W -
545208N 0045404W
Upper limit: 35000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9011111111,54.8688888889,10668 -4.9480555556,54.8313888889,10668 -4.9408333333,54.7613888889,10668 -4.8941666667,54.7041666667,10668 -4.8422222222,54.6686111111,10668 -4.7813888889,54.6541666667,10668 -4.5952777778,54.6805555556,10668 -4.5833333333,54.7177777778,10668 -4.6436111111,54.7805555556,10668 -4.8275,54.83555555560001,10668 -4.8294444444,54.85,10668 -4.8594444444,54.8713888889,10668 -4.9011111111,54.8688888889,10668 + + + + +
+ + EGD405 KIRKCUDBRIGHT + 544647N 0040349W -
544744N 0040214W -
544828N 0040040W -
544818N 0035705W -
544710N 0035630W -
543800N 0034806W -
543302N 0035720W -
543315N 0041341W -
543537N 0041514W -
544647N 0040349W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 15,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 50,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Kirkcudbright Range TSO, Tel: 01412-248500. DTSO 01412-248501.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0636111111,54.7797222222,15240 -4.2538888889,54.5936111111,15240 -4.2280555556,54.5541666667,15240 -3.9555555556,54.5505555556,15240 -3.8016666667,54.6333333333,15240 -3.9416666667,54.7861111111,15240 -3.9513888889,54.80499999999999,15240 -4.0111111111,54.80777777779999,15240 -4.0372222222,54.7955555556,15240 -4.0636111111,54.7797222222,15240 + + + + +
+ + EGD406A ESKMEALS + 542057N 0032747W thence clockwise by the arc of a circle radius 2 NM centred on 541900N 0032705W to
541701N 0032723W -
540634N 0033920W thence clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to
542357N 0034917W -
542846N 0033842W -
542057N 0032747W
Upper limit: 80000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 50,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Remarks: Aircraft following the west coast may proceed through the Danger Area at a height not below 2000 FT but it is essential that they remain east of the main railway line paralleling the coast while within the Danger Area. SI 1982/1180.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4630555556,54.3491666667,24384 -3.645,54.4794444444,24384 -3.821388888900001,54.3991666667,24384 -3.8264346983,54.3902456908,24384 -3.8308435947,54.381210064,24384 -3.8346650828,54.3720838636,24384 -3.8378941188,54.3628800713,24384 -3.8405265112,54.353611771,24384 -3.8425589244,54.3442921289,24384 -3.8439888809,54.3349343758,24384 -3.8448147631,54.3255517871,24384 -3.8450358126,54.3161576648,24384 -3.8446521295,54.306765318,24384 -3.8436646694,54.29738804439999,24384 -3.8420752404,54.2880391114,24384 -3.839886497400001,54.2787317371,24384 -3.8371019368,54.2694790723,24384 -3.8337258888,54.26029418169999,24384 -3.8297635095,54.2511900257,24384 -3.8252207712,54.24217944219999,24384 -3.8201044522,54.233275129,24384 -3.814422124900001,54.2244896262,24384 -3.8081821439,54.2158352985,24384 -3.801393632,54.2073243185,24384 -3.794066465599999,54.19896864990001,24384 -3.7862112598,54.19078003090001,24384 -3.7778393517,54.1827699581,24384 -3.7689627833,54.1749496712,24384 -3.7595942835,54.1673301372,24384 -3.7497472491,54.1599220357,24384 -3.7394357252,54.1527357444,24384 -3.7286743851,54.14578132510001,24384 -3.7174785086,54.1390685101,24384 -3.7058639609,54.1326066888,24384 -3.693847169300001,54.1264048954,24384 -3.6814451008,54.12047179679999,24384 -3.6686752382,54.1148156806,24384 -3.6555555556,54.1094444444,24384 -3.4563888889,54.2836111111,24384 -3.4506623994,54.2834617223,24384 -3.4449398451,54.2836739162,24384 -3.4392829629,54.28422262110001,24384 -3.433749363,54.28510224950001,24384 -3.428395409000001,54.2863038428,24384 -3.4232756474,54.2878151632,24384 -3.4184422552,54.2896208163,24384 -3.4139445105,54.291702408,24384 -3.409828292199999,54.2940387298,24384 -3.4061356127,54.2966059743,24384 -3.4029041892,54.2993779763,24384 -3.4001670583,54.3023264784,24384 -3.397952236,54.3054214177,24384 -3.396282429,54.3086312313,24384 -3.3951747988,54.3119231776,24384 -3.3946407821,54.3152636691,24384 -3.3946859681,54.318618615,24384 -3.3953100364,54.3219537687,24384 -3.396506754399999,54.3252350775,24384 -3.3982640352,54.32842903030001,24384 -3.4005640558,54.3315030008,24384 -3.4033834341,54.334425581,24384 -3.4066934642,54.3371669033,24384 -3.410460405999999,54.339698947,24384 -3.4146458278,54.3419958252,24384 -3.4192069976,54.34403405159999,24384 -3.4240973199,54.3457927812,24384 -3.429266812799999,54.3472540251,24384 -3.434662620600001,54.3484028352,24384 -3.4402295569,54.3492274587,24384 -3.4459106726,54.3497194586,24384 -3.4516478419,54.3498738009,24384 -3.4573823616,54.3496889063,24384 -3.4630555556,54.3491666667,24384 + + + + +
+ + EGD406B ESKMEALS + 541913N 0035042W thence anti-clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to
541049N 0034630W -
540804N 0035336W thence clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to
541916N 0035914W -
541913N 0035042W
Upper limit: 80000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 50,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.845,54.3202777778,24384 -3.9872222222,54.3211111111,24384 -3.9871594946,54.3107175685,24384 -3.9864927438,54.3003308501,24384 -3.985272219,54.2899613462,24384 -3.9834995252,54.2796191549,24384 -3.9811768014,54.26931434,24384 -3.9783067165,54.2590569217,24384 -3.9748924651,54.2488568664,24384 -3.970937763199999,54.23872407790001,24384 -3.9664468432,54.2286683871,24384 -3.9614244476,54.21869954340001,24384 -3.955875824,54.2088272049,24384 -3.9498067176,54.1990609292,24384 -3.9432233654,54.189410165,24384 -3.936132488,54.1798842425,24384 -3.9285412827,54.17049236490001,24384 -3.9204574148,54.1612435998,24384 -3.9118890095,54.15214687069999,24384 -3.902844642999999,54.1432109488,24384 -3.8933333333,54.1344444444,24384 -3.775,54.1802777778,24384 -3.7834591208,54.18808690669999,24384 -3.7913702592,54.1960923758,24384 -3.7987730162,54.2042637884,24384 -3.8056570042,54.2125900125,24384 -3.8120125251,54.2210596989,24384 -3.8178305841,54.2296612956,24384 -3.8231029043,54.2383830637,24384 -3.827821939,54.24721309289999,24384 -3.831980884,54.25613931740001,24384 -3.8355736883,54.2651495321,24384 -3.838595064899999,54.27423140929999,24384 -3.8410404991,54.2833725151,24384 -3.8429062576,54.2925603262,24384 -3.8441893949,54.30178224709999,24384 -3.8448877597,54.3110256271,24384 -3.845,54.3202777778,24384 + + + + +
+ + EGD406C ESKMEALS + 541916N 0035914W thence anti-clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to
540804N 0035336W -
541027N 0040844W thence clockwise by the arc of a circle radius 27 NM centred on 541900N 0032505W to
541413N 0041025W -
541916N 0035914W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9872222222,54.3211111111,15240 -4.1736111111,54.2369444444,15240 -4.1699727629,54.2263311513,15240 -4.1659452033,54.2157666889,15240 -4.1614866885,54.20526197990001,15240 -4.1566001131,54.1948230752,15240 -4.1512886114,54.1844559832,15240 -4.1455555556,54.1741666667,15240 -3.8933333333,54.1344444444,15240 -3.902802936100001,54.1432260183,15240 -3.9118465154,54.1521611714,15240 -3.920414174,54.1612571176,15240 -3.9284973363,54.17050508660001,15240 -3.936087878,54.1798961556,15240 -3.9431781344,54.1894212578,15240 -3.949760909,54.1990711908,15240 -3.9558294816,54.208836625,15240 -3.961377616,54.2187081128,15240 -3.9663995673,54.2286760972,15240 -3.9708900887,54.23873092099999,15240 -3.9748444377,54.2488628357,15240 -3.9782583827,54.2590620111,15240 -3.981128208,54.2693185444,15240 -3.9834507192,54.27962247,15240 -3.9852232477,54.2899637685,15240 -3.9864436549,54.300332377,15240 -3.9871103357,54.31071819839999,15240 -3.9872222222,54.3211111111,15240 + + + + +
+ + EGD407 WARCOP + 543812N 0022047W -
543856N 0021445W -
543753N 0021402W -
543432N 0021545W -
543156N 0022043W -
543202N 0022209W -
543343N 0022536W -
543526N 0022419W -
543812N 0022047W
Upper limit: 13500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 10,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 13,500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01768-343224.

Remarks: SI 1981/623.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3463888889,54.6366666667,4114.8 -2.4052777778,54.5905555556,4114.8 -2.4266666667,54.56194444440001,4114.8 -2.3691666667,54.5338888889,4114.8 -2.3452777778,54.5322222222,4114.8 -2.2625,54.5755555556,4114.8 -2.2338888889,54.6313888889,4114.8 -2.2458333333,54.64888888889999,4114.8 -2.3463888889,54.6366666667,4114.8 + + + + +
+ + EGD408 FELDOM + 542826N 0015159W -
542750N 0014921W -
542656N 0014654W -
542513N 0014819W -
542447N 0015004W -
542505N 0015159W -
542720N 0015350W -
542826N 0015159W
Upper limit: 5600 FT MSL
Lower limit: SFC
Class: Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 5600 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/ BVLOS) (less than 150 KTS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.

Remarks: SI 1976/566.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8663888889,54.47388888889999,1706.88 -1.8972222222,54.45555555560001,1706.88 -1.8663888889,54.4180555556,1706.88 -1.8344444444,54.4130555556,1706.88 -1.8052777778,54.4202777778,1706.88 -1.7816666667,54.4488888889,1706.88 -1.8225,54.4638888889,1706.88 -1.8663888889,54.47388888889999,1706.88 + + + + +
+ + EGD410 STRENSALL + A circle, 3000 FT radius, centred at 540136N 0010101W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01904-442966.

Remarks: SI 1972/246.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0169444444,54.03488188850001,304.8 -1.0197537238,54.0347136897,304.8 -1.0224479252,54.0342159834,304.8 -1.0249166926,54.03340915700001,304.8 -1.027058919,54.0323262586,304.8 -1.0287868913,54.0310116417,304.8 -1.0300298828,54.0295191457,304.8 -1.0307370464,54.0279098892,304.8 -1.0308794896,54.0262497647,304.8 -1.0304514472,54.0246067401,304.8 -1.0294705074,54.023048075,304.8 -1.0279768809,54.0216375685,304.8 -1.0260317464,54.0204329494,304.8 -1.0237147413,54.0194835154,304.8 -1.0211207007,54.018828118,304.8 -1.0183557787,54.01849357499999,304.8 -1.0155331101,54.01849357499999,304.8 -1.0127681882,54.018828118,304.8 -1.0101741476,54.0194835154,304.8 -1.0078571425,54.0204329494,304.8 -1.005912008,54.0216375685,304.8 -1.0044183814,54.023048075,304.8 -1.0034374417,54.0246067401,304.8 -1.0030093993,54.0262497647,304.8 -1.0031518424,54.0279098892,304.8 -1.0038590061,54.0295191457,304.8 -1.0051019976,54.0310116417,304.8 -1.0068299699,54.0323262586,304.8 -1.0089721963,54.03340915700001,304.8 -1.0114409637,54.0342159834,304.8 -1.0141351651,54.0347136897,304.8 -1.0169444444,54.03488188850001,304.8 + + + + +
+ + EGD412 STAXTON + 545800N 0002300W -
552500N 0010000E -
550400N 0012100E -
544545N 0005455E following the line of latitude to -
544545N 0000917W -
545800N 0002300W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3833333333,54.96666666669999,3048 -0.1547222222,54.76250000000001,3048 -0.0018650794,54.76250000000001,3048 0.1509920635,54.76250000000001,3048 0.3038492063,54.76250000000001,3048 0.4567063492,54.76250000000001,3048 0.6095634921,54.76250000000001,3048 0.7624206349,54.76250000000001,3048 0.9152777778000001,54.76250000000001,3048 1.35,55.0666666667,3048 1,55.4166666667,3048 -0.3833333333,54.96666666669999,3048 + + + + +
+ + EGD442 BELLERBY + A circle, 2300 M radius, centred at 542039N 0015125W
Upper limit: 3000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) (less than 150 KTS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.

Remarks: SI 1984/1770.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8569444444,54.36482938370001,914.4000000000001 -1.8615629685,54.3646525232,914.4000000000001 -1.8661023509,54.3641249725,914.4000000000001 -1.8704848124,54.3632557713,914.4000000000001 -1.874635274,54.3620598126,914.4000000000001 -1.8784826481,54.3605575869,914.4000000000001 -1.8819610599,54.35877482949999,914.4000000000001 -1.8850109775,54.3567420778,914.4000000000001 -1.8875802316,54.3544941467,914.4000000000001 -1.8896249068,54.3520695308,914.4000000000001 -1.8911100904,54.3495097429,914.4000000000001 -1.8920104643,54.3468586027,914.4000000000001 -1.8923107321,54.34416148500001,914.4000000000001 -1.8920058734,54.3414645427,914.4000000000001 -1.8911012215,54.3388139166,914.4000000000001 -1.8896123644,54.3362549466,914.4000000000001 -1.8875648703,54.33383139639999,914.4000000000001 -1.8849938442,54.3315847065,914.4000000000001 -1.8819433222,54.3295532866,914.4000000000001 -1.8784655147,54.3277718611,914.4000000000001 -1.8746199127,54.3262708765,914.4000000000001 -1.8704722699,54.3250759836,914.4000000000001 -1.8660934821,54.32420760019999,914.4000000000001 -1.8615583776,54.3236805636,914.4000000000001 -1.8569444444,54.3235038785,914.4000000000001 -1.8523305113,54.3236805636,914.4000000000001 -1.8477954068,54.32420760019999,914.4000000000001 -1.8434166189,54.3250759836,914.4000000000001 -1.8392689762,54.3262708765,914.4000000000001 -1.8354233741,54.3277718611,914.4000000000001 -1.8319455667,54.3295532866,914.4000000000001 -1.8288950447,54.3315847065,914.4000000000001 -1.8263240186,54.33383139639999,914.4000000000001 -1.8242765245,54.3362549466,914.4000000000001 -1.8227876674,54.3388139166,914.4000000000001 -1.8218830155,54.3414645427,914.4000000000001 -1.8215781568,54.34416148500001,914.4000000000001 -1.8218784246,54.3468586027,914.4000000000001 -1.8227787985,54.3495097429,914.4000000000001 -1.8242639821,54.3520695308,914.4000000000001 -1.8263086573,54.3544941467,914.4000000000001 -1.8288779114,54.3567420778,914.4000000000001 -1.831927829,54.35877482949999,914.4000000000001 -1.8354062408,54.3605575869,914.4000000000001 -1.8392536149,54.3620598126,914.4000000000001 -1.8434040765,54.3632557713,914.4000000000001 -1.847786538,54.3641249725,914.4000000000001 -1.8523259204,54.3646525232,914.4000000000001 -1.8569444444,54.36482938370001,914.4000000000001 + + + + +
+ + EGD505 MAGILLIGAN + 551117N 0065827W -
551307N 0065423W -
551253N 0065133W -
551107N 0064948W -
551010N 0065158W -
551008N 0065633W -
551117N 0065827W
Upper limit: 6500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 6500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 02877-720029.

Remarks: SI 1940/949.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.9741666667,55.18805555559999,1981.2 -6.942499999999999,55.1688888889,1981.2 -6.866111111099999,55.16944444439999,1981.2 -6.83,55.1852777778,1981.2 -6.8591666667,55.2147222222,1981.2 -6.9063888889,55.21861111110001,1981.2 -6.9741666667,55.18805555559999,1981.2 + + + + +
+ + EGD508 RIDSDALE + A circle, 1200 M radius, centred at 550845N 0021007W
Upper limit: 4100 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUACS: Newcastle APP on 124.380 MHz. SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Reception, Tel: 01434-220952.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1686111111,55.1566124562,1249.68 -2.1719724508,55.1564391851,1249.68 -2.1752256692,55.1559249452,1249.68 -2.178266131,55.15508627719999,1249.68 -2.1809960593,55.15395015599999,1249.68 -2.1833276853,55.15255312059999,1249.68 -2.1851860725,55.15094009760001,1249.68 -2.186511525,55.14916295340001,1249.68 -2.1872615013,55.14727882470001,1249.68 -2.1874119744,55.14534827960001,1249.68 -2.1869581941,55.14343336949999,1249.68 -2.1859148286,55.1415956348,1249.68 -2.1843154823,55.13989412720001,1249.68 -2.182211607,55.1383835141,1249.68 -2.1796708423,55.13711232389999,1249.68 -2.1767748386,55.13612138940001,1249.68 -2.1736166351,55.1354425383,1249.68 -2.1702976739,55.1350975733,1249.68 -2.1669245483,55.1350975733,1249.68 -2.1636055872,55.1354425383,1249.68 -2.1604473836,55.13612138940001,1249.68 -2.15755138,55.13711232389999,1249.68 -2.1550106152,55.1383835141,1249.68 -2.1529067399,55.13989412720001,1249.68 -2.1513073936,55.1415956348,1249.68 -2.1502640281,55.14343336949999,1249.68 -2.1498102478,55.14534827960001,1249.68 -2.149960721,55.14727882470001,1249.68 -2.1507106972,55.14916295340001,1249.68 -2.1520361497,55.15094009760001,1249.68 -2.1538945369,55.15255312059999,1249.68 -2.1562261629,55.15395015599999,1249.68 -2.1589560912,55.15508627719999,1249.68 -2.161996553,55.1559249452,1249.68 -2.1652497714,55.1564391851,1249.68 -2.1686111111,55.1566124562,1249.68 + + + + +
+ + EGD509 CAMPBELTOWN + 551230N 0053900W following the line of latitude to -
551230N 0050636W -
550706N 0050700W -
545930N 0051542W -
545548N 0052800W -
550630N 0054300W -
551230N 0053900W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: CTF311 Operations, Tel: 01923-956371.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.65,55.2083333333,16764 -5.7166666667,55.1083333333,16764 -5.4666666667,54.92999999999999,16764 -5.2616666667,54.9916666667,16764 -5.1166666667,55.1183333333,16764 -5.11,55.2083333333,16764 -5.245,55.2083333333,16764 -5.38,55.2083333333,16764 -5.515,55.2083333333,16764 -5.65,55.2083333333,16764 + + + + +
+ + EGD510A SPADEADAM + 551500N 0025256W -
550112N 0024453W -
550900N 0030000W -
551500N 0025400W -
551500N 0025256W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 15,000 FT ALT by NOTAM.

Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8821305556,55.25,4572 -2.9,55.25,4572 -3,55.15,4572 -2.7480777778,55.01992500000001,4572 -2.8821305556,55.25,4572 + + + + +
+ + EGD510B SPADEADAM + 551500N 0025256W -
551500N 0023951W -
550453N 0021743W -
550417N 0021717W -
550206N 0021640W -
550000N 0022752W -
550000N 0024235W -
550112N 0024453W -
551500N 0025256W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.

Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8821305556,55.25,5486.400000000001 -2.7480777778,55.01992500000001,5486.400000000001 -2.7097222222,55.00000000000001,5486.400000000001 -2.4644444444,55.00000000000001,5486.400000000001 -2.2777777778,55.035,5486.400000000001 -2.2880555556,55.0713888889,5486.400000000001 -2.2952777778,55.0813888889,5486.400000000001 -2.6641666667,55.25,5486.400000000001 -2.8821305556,55.25,5486.400000000001 + + + + +
+ + EGD510C SPADEADAM + A circle, 1.5 NM radius, centred at 550243N 0023526W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Remarks: When EGD510C is activated in isolation from EGD510B, Unmanned Aircraft System (BVLOS) operations are not permitted.
When EGD510B is activated by NOTAM, EGD510C will also be activated for the same period and to the same altitude.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.59065,55.0702401658,5486.400000000001 -2.5957932319,55.0700649075,5486.400000000001 -2.6008641309,55.0695415973,5486.400000000001 -2.6057913869,55.0686775946,5486.400000000001 -2.6105057207,55.0674850495,5486.400000000001 -2.614940863,55.0659807311,5486.400000000001 -2.6190344894,55.06418579,5486.400000000001 -2.6227290992,55.0621254604,5486.400000000001 -2.6259728243,55.05982870279999,5486.400000000001 -2.6287201577,55.0573277963,5486.400000000001 -2.6309325909,55.05465788240001,5486.400000000001 -2.6325791506,55.0518564705,5486.400000000001 -2.6336368295,55.04896290960001,5486.400000000001 -2.6340909028,55.0460178342,5486.400000000001 -2.6339351282,55.0430625935,5486.400000000001 -2.6331718261,55.0401386701,5486.400000000001 -2.6318118396,55.0372870984,5486.400000000001 -2.6298743751,55.0345478888,5486.400000000001 -2.6273867262,55.031959467,5486.400000000001 -2.6243838853,55.0295581366,5486.400000000001 -2.6209080484,55.02737757089999,5486.400000000001 -2.6170080203,55.025448342,5486.400000000001 -2.612738529,55.02379749459999,5486.400000000001 -2.6081594582,55.0224481674,5486.400000000001 -2.6033350102,55.0214192711,5486.400000000001 -2.5983328083,55.0207252243,5486.400000000001 -2.5932229534,55.0203757525,5486.400000000001 -2.5880770466,55.0203757525,5486.400000000001 -2.5829671917,55.0207252243,5486.400000000001 -2.5779649898,55.0214192711,5486.400000000001 -2.5731405418,55.0224481674,5486.400000000001 -2.568561471,55.02379749459999,5486.400000000001 -2.5642919797,55.025448342,5486.400000000001 -2.5603919516,55.02737757089999,5486.400000000001 -2.5569161147,55.0295581366,5486.400000000001 -2.5539132738,55.031959467,5486.400000000001 -2.5514256249,55.0345478888,5486.400000000001 -2.5494881604,55.0372870984,5486.400000000001 -2.5481281739,55.0401386701,5486.400000000001 -2.5473648718,55.0430625935,5486.400000000001 -2.5472090972,55.0460178342,5486.400000000001 -2.5476631705,55.04896290960001,5486.400000000001 -2.5487208494,55.0518564705,5486.400000000001 -2.5503674091,55.05465788240001,5486.400000000001 -2.5525798423,55.0573277963,5486.400000000001 -2.5553271757,55.05982870279999,5486.400000000001 -2.5585709008,55.0621254604,5486.400000000001 -2.5622655106,55.06418579,5486.400000000001 -2.566359137,55.0659807311,5486.400000000001 -2.5707942793,55.0674850495,5486.400000000001 -2.5755086131,55.0686775946,5486.400000000001 -2.5804358691,55.0695415973,5486.400000000001 -2.5855067681,55.0700649075,5486.400000000001 -2.59065,55.0702401658,5486.400000000001 + + + + +
+ + EGD512A OTTERBURN + 551418N 0020239W -
551054N 0021311W -
551615N 0022552W -
551857N 0022315W -
551525N 0021352W -
551418N 0020239W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.

Remarks: SI 1971/919 and SI 1980/38.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0441666667,55.2383333333,6705.599999999999 -2.2311111111,55.2569444444,6705.599999999999 -2.3875,55.31583333329999,6705.599999999999 -2.4311111111,55.2708333333,6705.599999999999 -2.2197222222,55.1816666667,6705.599999999999 -2.0441666667,55.2383333333,6705.599999999999 + + + + +
+ + EGD512B OTTERBURN + 552426N 0021355W -
551719N 0020336W -
551418N 0020239W -
551525N 0021352W -
551857N 0022315W -
552212N 0022009W -
552426N 0021355W
Upper limit: 25000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 18,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 25,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.

Remarks: SI 1971/919 and SI 1980/38.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2319444444,55.40722222219999,7620 -2.3358333333,55.37,7620 -2.3875,55.31583333329999,7620 -2.2311111111,55.2569444444,7620 -2.0441666667,55.2383333333,7620 -2.06,55.2886111111,7620 -2.2319444444,55.40722222219999,7620 + + + + +
+ + EGD513A DRURIDGE BAY + 550200N 0010000W -
552000N 0010640W -
552000N 0002300W -
550200N 0004000W -
550200N 0010000W
Upper limit: FL230
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1,55.0333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -1,55.0333333333,7010.400000000001 + + + + +
+ + EGD513B DRURIDGE BAY + 554400N 0011543W -
554400N 0000726E -
552000N 0001700E -
550200N 0004000W -
552000N 0002300W -
552000N 0010640W -
554400N 0011543W
Upper limit: FL230
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2619444444,55.7333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 0.2833333333,55.3333333333,7010.400000000001 0.1238888889,55.7333333333,7010.400000000001 -1.2619444444,55.7333333333,7010.400000000001 + + + + +
+ + EGD513C DRURIDGE BAY + 555000N 0011800W -
555000N 0000500E -
552000N 0001700E -
550200N 0004000W -
550200N 0010000W -
555000N 0011800W
Upper limit: FL100
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3,55.8333333333,3048 -1,55.0333333333,3048 -0.6666666667,55.0333333333,3048 0.2833333333,55.3333333333,3048 0.08333333330000001,55.8333333333,3048 -1.3,55.8333333333,3048 + + + + +
+ + EGD514 COMBAT AIRSPACE + 564944N 0023059W -
561522N 0003908E -
554828N 0020148E -
542337N 0012225E -
550310N 0010229W -
550419N 0010503W thence anti-clockwise by the arc of a circle radius 21 NM centred on 550217N 0014123W to
551920N 0012007W -
551610N 0013433W -
551426N 0014100W -
551403N 0014229W -
552952N 0023047W -
553928N 0024212W -
560122N 0023945W -
561317N 0025226W -
563754N 0024601W -
564944N 0023059W
Upper limit: FL660
Lower limit: FL85
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 119.875 MHz and London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,20116.8 -2.7668234167,56.6316858611,20116.8 -2.8739837778,56.22139349999999,20116.8 -2.6626117778,56.0226490556,20116.8 -2.7031990833,55.6578733611,20116.8 -2.5130380278,55.49769625,20116.8 -1.7079248333,55.2341564444,20116.8 -1.683344,55.24068008330001,20116.8 -1.5759322778,55.2693510278,20116.8 -1.3351568333,55.32227475,20116.8 -1.3196354763,55.3157079327,20116.8 -1.304490274,55.3088632909,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2753887059,55.29436858319999,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2223387981,55.26236881040001,20116.8 -1.2102274184,55.25378864080001,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1481271314,55.19810933120001,20116.8 -1.13963258,55.1882171739,20116.8 -1.1316917604,55.17817610270001,20116.8 -1.1243122408,55.16799621880001,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1056084054,55.13672661809999,20116.8 -1.1005380561,55.1260949743,20116.8 -1.096058024,55.1153767893,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0414236389,55.0526792778,20116.8 1.3735272222,54.3935690833,20116.8 2.0298775556,55.8078658611,20116.8 0.6521053333,56.2561136389,20116.8 -2.5163368333,56.8287937778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.22139349999999,2590.8 -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.683344,55.24068008330001,2590.8 -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.29436858319999,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.26236881040001,2590.8 -1.2102274184,55.25378864080001,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.19810933120001,2590.8 -1.13963258,55.1882171739,2590.8 -1.1316917604,55.17817610270001,2590.8 -1.1243122408,55.16799621880001,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.13672661809999,2590.8 -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.7668234167,56.6316858611,20116.8 -2.5163368333,56.8287937778,20116.8 -2.5163368333,56.8287937778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.22139349999999,2590.8 -2.8739837778,56.22139349999999,20116.8 -2.7668234167,56.6316858611,20116.8 -2.7668234167,56.6316858611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.8739837778,56.22139349999999,2590.8 -2.6626117778,56.0226490556,2590.8 -2.6626117778,56.0226490556,20116.8 -2.8739837778,56.22139349999999,20116.8 -2.8739837778,56.22139349999999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.7031990833,55.6578733611,20116.8 -2.6626117778,56.0226490556,20116.8 -2.6626117778,56.0226490556,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -2.5130380278,55.49769625,20116.8 -2.7031990833,55.6578733611,20116.8 -2.7031990833,55.6578733611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.7079248333,55.2341564444,20116.8 -2.5130380278,55.49769625,20116.8 -2.5130380278,55.49769625,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.7079248333,55.2341564444,2590.8 -1.683344,55.24068008330001,2590.8 -1.683344,55.24068008330001,20116.8 -1.7079248333,55.2341564444,20116.8 -1.7079248333,55.2341564444,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.683344,55.24068008330001,2590.8 -1.5759322778,55.2693510278,2590.8 -1.5759322778,55.2693510278,20116.8 -1.683344,55.24068008330001,20116.8 -1.683344,55.24068008330001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3351568333,55.32227475,20116.8 -1.5759322778,55.2693510278,20116.8 -1.5759322778,55.2693510278,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.3196354763,55.3157079327,20116.8 -1.3351568333,55.32227475,20116.8 -1.3351568333,55.32227475,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.304490274,55.3088632909,20116.8 -1.3196354763,55.3157079327,20116.8 -1.3196354763,55.3157079327,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2897364284,55.3017477663,20116.8 -1.304490274,55.3088632909,20116.8 -1.304490274,55.3088632909,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.29436858319999,2590.8 -1.2753887059,55.29436858319999,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2897364284,55.3017477663,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2753887059,55.29436858319999,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2614614361,55.2867332297,20116.8 -1.2753887059,55.29436858319999,20116.8 -1.2753887059,55.29436858319999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2479684983,55.2788494494,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2614614361,55.2867332297,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2349233067,55.2707252331,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2479684983,55.2788494494,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.26236881040001,2590.8 -1.2223387981,55.26236881040001,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2349233067,55.2707252331,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2223387981,55.26236881040001,2590.8 -1.2102274184,55.25378864080001,2590.8 -1.2102274184,55.25378864080001,20116.8 -1.2223387981,55.26236881040001,20116.8 -1.2223387981,55.26236881040001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2102274184,55.25378864080001,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1986011112,55.2449934046,20116.8 -1.2102274184,55.25378864080001,20116.8 -1.2102274184,55.25378864080001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1874713062,55.2359919941,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1986011112,55.2449934046,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1768489084,55.2267935037,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1874713062,55.2359919941,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1667442882,55.2174072208,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1768489084,55.2267935037,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1571672715,55.2078426155,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1667442882,55.2174072208,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.19810933120001,2590.8 -1.1481271314,55.19810933120001,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1571672715,55.2078426155,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1481271314,55.19810933120001,2590.8 -1.13963258,55.1882171739,2590.8 -1.13963258,55.1882171739,20116.8 -1.1481271314,55.19810933120001,20116.8 -1.1481271314,55.19810933120001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.13963258,55.1882171739,2590.8 -1.1316917604,55.17817610270001,2590.8 -1.1316917604,55.17817610270001,20116.8 -1.13963258,55.1882171739,20116.8 -1.13963258,55.1882171739,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1316917604,55.17817610270001,2590.8 -1.1243122408,55.16799621880001,2590.8 -1.1243122408,55.16799621880001,20116.8 -1.1316917604,55.17817610270001,20116.8 -1.1316917604,55.17817610270001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1243122408,55.16799621880001,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1175010074,55.1576877554,20116.8 -1.1243122408,55.16799621880001,20116.8 -1.1243122408,55.16799621880001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1112644597,55.1472610668,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1175010074,55.1576877554,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.13672661809999,2590.8 -1.1056084054,55.13672661809999,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1112644597,55.1472610668,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1056084054,55.13672661809999,2590.8 -1.1005380561,55.1260949743,2590.8 -1.1005380561,55.1260949743,20116.8 -1.1056084054,55.13672661809999,20116.8 -1.1056084054,55.13672661809999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.096058024,55.1153767893,20116.8 -1.1005380561,55.1260949743,20116.8 -1.1005380561,55.1260949743,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0921723192,55.1045827952,20116.8 -1.096058024,55.1153767893,20116.8 -1.096058024,55.1153767893,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0888843473,55.0937237913,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0921723192,55.1045827952,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0861969081,55.0828106334,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0888843473,55.0937237913,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0841121944,55.0718542222,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0861969081,55.0828106334,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 -1.0414236389,55.0526792778,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0841121944,55.0718542222,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 1.3735272222,54.3935690833,20116.8 -1.0414236389,55.0526792778,20116.8 -1.0414236389,55.0526792778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 2.0298775556,55.8078658611,20116.8 1.3735272222,54.3935690833,20116.8 1.3735272222,54.3935690833,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 0.6521053333,56.2561136389,20116.8 2.0298775556,55.8078658611,20116.8 2.0298775556,55.8078658611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 -2.5163368333,56.8287937778,20116.8 0.6521053333,56.2561136389,20116.8 0.6521053333,56.2561136389,2590.8 + + + + + +
+ + EGD601 GARELOCHHEAD + 560805N 0044636W -
560505N 0044656W -
560440N 0044740W -
560547N 0044912W -
560706N 0044912W -
560805N 0044636W
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01412-248123.

Danger Area Authority: DIO.

Remarks: UAS BVLOS will not be conducted above 1500 FT ALT.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7766666667,56.1347222222,1219.2 -4.82,56.11833333329999,1219.2 -4.82,56.0963888889,1219.2 -4.7944444444,56.0777777778,1219.2 -4.7822222222,56.0847222222,1219.2 -4.7766666667,56.1347222222,1219.2 + + + + +
+ + EGD604 BARRY BUDDON + 562849N 0024849W -
562957N 0024010W -
562735N 0023943W -
562738N 0024829W -
562849N 0024849W
Upper limit: 9000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 9000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Leuchars APP on 126.500 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-103426.

Remarks: SI 1973/1428. UAS BVLOS will not be conducted above 3000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.813611111100001,56.4802777778,2743.2 -2.8080555556,56.4605555556,2743.2 -2.6619444444,56.45972222219999,2743.2 -2.6694444444,56.49916666670001,2743.2 -2.813611111100001,56.4802777778,2743.2 + + + + +
+ + EGD613A CENTRAL COMPLEX + 574421N 0002631E -
571940N 0004851E -
564725N 0013559W -
571447N 0014618W -
574421N 0002631E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,20116.8 -1.7715583333,57.2462805556,20116.8 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.4419305556,57.7391472222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,3048 -1.7715583333,57.2462805556,3048 -1.5996,56.7901638889,3048 0.8140888889,57.32785,3048 0.4419305556,57.7391472222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,3048 -1.7715583333,57.2462805556,3048 -1.7715583333,57.2462805556,20116.8 0.4419305556,57.7391472222,20116.8 0.4419305556,57.7391472222,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.7715583333,57.2462805556,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 -1.7715583333,57.2462805556,20116.8 -1.7715583333,57.2462805556,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 0.8140888889,57.32785,3048 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 0.4419305556,57.7391472222,3048 0.4419305556,57.7391472222,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048 + + + + + +
+ + EGD613B CENTRAL COMPLEX + 571940N 0004851E -
565256N 0011225E -
564725N 0013559W -
571940N 0004851E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 0.8140888889,57.32785,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 -1.5996,56.7901638889,3048 1.2068416667,56.8823361111,3048 0.8140888889,57.32785,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 0.8140888889,57.32785,3048 0.8140888889,57.32785,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + +
+ + EGD613C CENTRAL COMPLEX + 565256N 0011225E -
561750N 0012507W -
564725N 0013559W -
565256N 0011225E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.5996,56.7901638889,3048 -1.4184805556,56.2971694444,3048 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 -1.4184805556,56.2971694444,3048 -1.4184805556,56.2971694444,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.4184805556,56.2971694444,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048 + + + + + +
+ + EGD613D CENTRAL COMPLEX + 565256N 0011225E -
560344N 0015411E -
560509N 0002907W -
561750N 0012507W -
565256N 0011225E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -0.4851527778,56.0857027778,20116.8 1.9031472222,56.0623555556,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.4184805556,56.2971694444,3048 -0.4851527778,56.0857027778,3048 1.9031472222,56.0623555556,3048 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.4184805556,56.2971694444,3048 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.4184805556,56.2971694444,3048 -0.4851527778,56.0857027778,3048 -0.4851527778,56.0857027778,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048 + + + + + + relativeToGround + + + relativeToGround + + -0.4851527778,56.0857027778,3048 1.9031472222,56.0623555556,3048 1.9031472222,56.0623555556,20116.8 -0.4851527778,56.0857027778,20116.8 -0.4851527778,56.0857027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.9031472222,56.0623555556,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 1.9031472222,56.0623555556,20116.8 1.9031472222,56.0623555556,3048 + + + + + +
+ + EGD701A HEBRIDES + 573347N 0074803W -
572253N 0072531W -
572324N 0072233W -
572147N 0072116W -
571056N 0072253W -
571034N 0073131W -
570200N 0073421W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
573347N 0074803W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.800833333299999,57.5630555556,30449.52 -7.8147936092,57.5556144002,30449.52 -7.8282732985,57.54792286990001,30449.52 -7.841261266,57.5399919141,30449.52 -7.8537430548,57.5318305591,30449.52 -7.8657048125,57.5234480871,30449.52 -7.877133306,57.51485402520001,30449.52 -7.8880159355,57.5060581345,30449.52 -7.8983407475,57.4970703978,30449.52 -7.9080964477,57.4879010084,30449.52 -7.9172724118,57.4785603579,30449.52 -7.925858696199999,57.4690590239,30449.52 -7.9338460477,57.4594077576,30449.52 -7.9412259119,57.4496174713,30449.52 -7.9479904416,57.4396992258,30449.52 -7.954132502800001,57.4296642173,30449.52 -7.9596456814,57.41952376460001,30449.52 -7.9645242879,57.40928929609999,30449.52 -7.9687633616,57.3989723365,30449.52 -7.972358674,57.3885844937,30449.52 -7.975306731,57.37813744549999,30449.52 -7.9776047746,57.36764292620001,30449.52 -7.9792507833,57.3571127135,30449.52 -7.980243472200001,57.3465586152,30449.52 -7.9805822915,57.3359924554,30449.52 -7.980267425,57.325426062,30449.52 -7.979299787,57.3148712527,30449.52 -7.9776810193,57.3043398224,30449.52 -7.9754134861,57.2938435297,30449.52 -7.9725002697,57.28339408400001,30449.52 -7.9689451642,57.2730031328,30449.52 -7.9647526688,57.2626822485,30449.52 -7.959927980999999,57.2524429158,30449.52 -7.954476987700001,57.2422965194,30449.52 -7.9484062576,57.2322543314,30449.52 -7.9417230308,57.222327499,30449.52 -7.934435209299999,57.2125270325,30449.52 -7.9265513463,57.2028637936,30449.52 -7.9180806346,57.1933484835,30449.52 -7.9090328952,57.1839916314,30449.52 -7.8994185645,57.1748035833,30449.52 -7.8892486813,57.1657944914,30449.52 -7.8785348735,57.1569743024,30449.52 -7.8672893439,57.148352748,30449.52 -7.8555248557,57.1399393337,30449.52 -7.8432547174,57.1317433295,30449.52 -7.8304927676,57.12377375980001,30449.52 -7.8172533586,57.116039394,30449.52 -7.803551340600001,57.1085487375,30449.52 -7.7894020448,57.1013100226,30449.52 -7.7748212661,57.0943312,30449.52 -7.7598252458,57.0876199308,30449.52 -7.7444306541,57.0811835783,30449.52 -7.7286545713,57.07502920040001,30449.52 -7.712514469999999,57.06916354269999,30449.52 -7.696028196,57.06359303100001,30449.52 -7.679213949500001,57.058323765,30449.52 -7.6620902657,57.0533615124,30449.52 -7.644675995300001,57.0487117023,30449.52 -7.626990285100001,57.0443794202,30449.52 -7.6090525576,57.0403694026,30449.52 -7.5908824912,57.0366860321,30449.52 -7.5725,57.03333333329999,30449.52 -7.5252777778,57.1761111111,30449.52 -7.381388888900001,57.18222222219999,30449.52 -7.3544444444,57.3630555556,30449.52 -7.3758333333,57.39000000000001,30449.52 -7.4252777778,57.3813888889,30449.52 -7.800833333299999,57.5630555556,30449.52 + + + + +
+ + EGD701B HEBRIDES + 570200N 0073421W -
565713N 0073556W -
571703N 0092047W -
574801N 0092039W -
574514N 0083032W -
574224N 0080606W -
573347N 0074803W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
570200N 0073421W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.5725,57.03333333329999,30449.52 -7.5908806376,57.0366888943,30449.52 -7.609050530599999,57.04037222969999,30449.52 -7.626988086899999,57.04438220909999,30449.52 -7.6446736282,57.04871444989999,30449.52 -7.6620877322,57.05336421570001,30449.52 -7.6792112525,57.058326421,30449.52 -7.6960253382,57.0635956367,30449.52 -7.7125114546,57.06916609529999,30449.52 -7.7286514014,57.07503169700001,30449.52 -7.7444273331,57.0811860162,30449.52 -7.7598217773,57.0876223072,30449.52 -7.7748176538,57.0943335124,30449.52 -7.7893982926,57.1013122683,30449.52 -7.8035474526,57.10855091410001,30449.52 -7.817249339,57.11604149910001,30449.52 -7.830488620599999,57.12377579100001,30449.52 -7.8432504477,57.1317452846,30449.52 -7.8555204677,57.13994121040001,30449.52 -7.8672848425,57.1483545443,30449.52 -7.8785302635,57.1569760164,30449.52 -7.8892439677,57.165796121,30449.52 -7.899413752499999,57.1748051268,30449.52 -7.9090279901,57.1839930869,30449.52 -7.9180756416,57.1933498495,30449.52 -7.9265462709,57.2028650685,30449.52 -7.9344300571,57.2125282149,30449.52 -7.9417178074,57.2223285875,30449.52 -7.9484009688,57.2322553248,30449.52 -7.954471639299999,57.2422974166,30449.52 -7.9599225788,57.25244371580001,30449.52 -7.964747219,57.2626829503,30449.52 -7.9689396726,57.27300373569999,30449.52 -7.972494742500001,57.2833945872,30449.52 -7.9754079293,57.2938439326,30449.52 -7.9776754391,57.30434012450001,30449.52 -7.9792941897,57.3148714537,30449.52 -7.9802618168,57.3254261616,30449.52 -7.9805766787,57.33599245359999,30449.52 -7.980237860999999,57.3465585118,30449.52 -7.9792451801,57.35711250869999,30449.52 -7.9775991856,57.3676426201,30449.52 -7.975301162499999,57.3781370385,30449.52 -7.972353132200001,57.3885839862,30449.52 -7.9687578529,57.3989717291,30449.52 -7.964518818399999,57.4092885894,30449.52 -7.9596402574,57.4195229594,30449.52 -7.9541271304,57.42966331440001,30449.52 -7.9479851269,57.4396982262,30449.52 -7.941220660999999,57.4496163762,30449.52 -7.933840866500001,57.4594065681,30449.52 -7.9258535907,57.46905774129999,30449.52 -7.9172673878,57.4785589837,30449.52 -7.908091510899999,57.4878995441,30449.52 -7.898335903599999,57.49706884499999,30449.52 -7.88801119,57.5060564949,30449.52 -7.877128664499999,57.5148523008,30449.52 -7.8657002803,57.5234462797,30449.52 -7.8537386371,57.5318286708,30449.52 -7.841256967800001,57.53998994690001,30449.52 -7.8282691249,57.547920826,30449.52 -7.814789565,57.555612282,30449.52 -7.800833333299999,57.5630555556,30449.52 -8.1016944444,57.7065416667,30449.52 -8.508827777800001,57.7539222222,30449.52 -9.3442027778,57.80035277780001,30449.52 -9.346377777800001,57.2840638889,30449.52 -7.5988888889,56.9536111111,30449.52 -7.5725,57.03333333329999,30449.52 + + + + +
+ + EGD701C HEBRIDES + 574801N 0092039W -
575639N 0081032W -
575154N 0074532W -
573809N 0073422W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to
573347N 0074803W -
574224N 0080606W -
574514N 0083032W -
574801N 0092039W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.3442027778,57.80035277780001,30449.52 -8.508827777800001,57.7539222222,30449.52 -8.1016944444,57.7065416667,30449.52 -7.800833333299999,57.5630555556,30449.52 -7.786893946,57.5700722445,30449.52 -7.772476361,57.5768067724,30449.52 -7.7576539429,57.58328442349999,30449.52 -7.7424424392,57.5894982237,30449.52 -7.7268580417,57.59544147929999,30449.52 -7.7109173688,57.601107785,30449.52 -7.6946374473,57.6064910309,30449.52 -7.6780356935,57.6115854099,30449.52 -7.6611298942,57.6163854238,30449.52 -7.6439381861,57.6208858901,30449.52 -7.6264790362,57.625081948,30449.52 -7.608771220300001,57.6289690637,30449.52 -7.590833802000001,57.63254303570001,30449.52 -7.572686111099999,57.6358,30449.52 -7.7588888889,57.865,30449.52 -8.175577777799999,57.9442055556,30449.52 -9.3442027778,57.80035277780001,30449.52 + + + + +
+ + EGD701D HEBRIDES + 571703N 0092047W -
565801N 0074000W -
564302N 0074000W -
565603N 0090000W -
571703N 0092047W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.346377777800001,57.2840638889,30449.52 -9,56.9342638889,30449.52 -7.666666666699999,56.7172722222,30449.52 -7.666666666699999,56.9669944444,30449.52 -9.346377777800001,57.2840638889,30449.52 + + + + +
+ + EGD701E HEBRIDES + 582859N 0094100W following the line of latitude to -
582859N 0084939W -
574923N 0071500W -
574128N 0073703W -
575154N 0074532W -
575639N 0081032W -
575411N 0083112W -
580439N 0085353W -
582859N 0094100W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.683422222200001,58.4831388889,30449.52 -8.898055555599999,58.0775,30449.52 -8.520127777800001,57.9030305556,30449.52 -8.175577777799999,57.9442055556,30449.52 -7.7588888889,57.865,30449.52 -7.6173694444,57.6910777778,30449.52 -7.250000000000001,57.82314722220001,30449.52 -8.8276361111,58.4831388889,30449.52 -8.9987933333,58.4831388889,30449.52 -9.1699505556,58.4831388889,30449.52 -9.3411077778,58.4831388889,30449.52 -9.512264999999999,58.4831388889,30449.52 -9.683422222200001,58.4831388889,30449.52 + + + + +
+ + EGD701F HEBRIDES + 593000N 0100000W -
584715N 0074914W -
582525N 0070835W -
574923N 0071500W -
582859N 0084939W following the line of latitude to -
582859N 0100000W -
593000N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,59.5,30449.52 -10,58.4831388889,30449.52 -9.832519444400001,58.4831388889,30449.52 -9.6650388889,58.4831388889,30449.52 -9.497558333300001,58.4831388889,30449.52 -9.3300777778,58.4831388889,30449.52 -9.162597222200001,58.4831388889,30449.52 -8.9951166667,58.4831388889,30449.52 -8.8276361111,58.4831388889,30449.52 -7.250000000000001,57.82314722220001,30449.52 -7.1430638889,58.4235972222,30449.52 -7.820622222200001,58.7873638889,30449.52 -10,59.5,30449.52 + + + + +
+ + EGD701G HEBRIDES + 582859N 0100000W following the line of latitude to -
582859N 0094100W -
580439N 0085353W -
575411N 0083112W -
574801N 0092039W -
571703N 0092047W -
573301N 0100000W -
582859N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,58.4831388889,30449.52 -10,57.5501444444,30449.52 -9.346377777800001,57.2840638889,30449.52 -9.3442027778,57.80035277780001,30449.52 -8.520127777800001,57.9030305556,30449.52 -8.898055555599999,58.0775,30449.52 -9.683422222200001,58.4831388889,30449.52 -9.8417111111,58.4831388889,30449.52 -10,58.4831388889,30449.52 + + + + +
+ + EGD701H HEBRIDES + 573301N 0100000W -
571703N 0092047W -
565603N 0090000W -
571500N 0100000W -
573301N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,57.5501444444,30449.52 -10,57.25,30449.52 -9,56.9342638889,30449.52 -9.346377777800001,57.2840638889,30449.52 -10,57.5501444444,30449.52 + + + + +
+ + EGD701I HEBRIDES + 571500N 0100000W -
565603N 0090000W -
564302N 0074000W -
563510N 0074307W -
563524N 0083728W -
564548N 0100000W -
571500N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,57.25,30449.52 -10,56.7633694444,30449.52 -8.624513888899999,56.5898861111,30449.52 -7.7185305556,56.5859805556,30449.52 -7.666666666699999,56.7172722222,30449.52 -9,56.9342638889,30449.52 -10,57.25,30449.52 + + + + +
+ + EGD701J HEBRIDES + 564548N 0100000W -
563524N 0083728W -
563510N 0074307W -
560339N 0074415W -
563523N 0100000W -
564548N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.7633694444,30449.52 -10,56.5896416667,30449.52 -7.7374527778,56.0608027778,30449.52 -7.7185305556,56.5859805556,30449.52 -8.624513888899999,56.5898861111,30449.52 -10,56.7633694444,30449.52 + + + + +
+ + EGD701K HEBRIDES + 563523N 0100000W -
560339N 0074415W -
555107N 0080000W following the line of latitude to -
555107N 0080331W -
562630N 0100000W -
563523N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.5896416667,30449.52 -10,56.4417388889,30449.52 -8.0585555556,55.8519,30449.52 -8,55.8519,30449.52 -7.7374527778,56.0608027778,30449.52 -10,56.5896416667,30449.52 + + + + +
+ + EGD701L HEBRIDES + 562630N 0100000W -
560435N 0084640W -
560530N 0100000W -
562630N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.4417388889,30449.52 -10,56.09176111110001,30449.52 -8.7777972222,56.0762722222,30449.52 -10,56.4417388889,30449.52 + + + + +
+ + EGD701M HEBRIDES + 560530N 0100000W -
560435N 0084640W -
555107N 0080331W following the line of latitude to -
555107N 0080000W -
554000N 0080000W following the line of latitude to -
554000N 0092508W -
554516N 0100000W -
560530N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.09176111110001,30449.52 -10,55.7545083333,30449.52 -9.4188888889,55.6666666667,30449.52 -9.261234567900001,55.6666666667,30449.52 -9.1035802469,55.6666666667,30449.52 -8.945925925899999,55.6666666667,30449.52 -8.7882716049,55.6666666667,30449.52 -8.630617284,55.6666666667,30449.52 -8.472962963000001,55.6666666667,30449.52 -8.315308642,55.6666666667,30449.52 -8.157654321000001,55.6666666667,30449.52 -8,55.6666666667,30449.52 -8,55.8519,30449.52 -8.0585555556,55.8519,30449.52 -8.7777972222,56.0762722222,30449.52 -10,56.09176111110001,30449.52 + + + + +
+ + EGD701N HEBRIDES + 563148N 0114510W -
560530N 0100000W -
554516N 0100000W -
555352N 0110000W -
563148N 0114510W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -11.7529138889,56.53005,30449.52 -11,55.8977805556,30449.52 -10,55.7545083333,30449.52 -10,56.09176111110001,30449.52 -11.7529138889,56.53005,30449.52 + + + + +
+ + EGD701O HEBRIDES + 570000N 0120000W -
562630N 0100000W -
560530N 0100000W -
563148N 0114510W -
564357N 0120000W -
570000N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57,30449.52 -12,56.7324472222,30449.52 -11.7529138889,56.53005,30449.52 -10,56.09176111110001,30449.52 -10,56.4417388889,30449.52 -12,57,30449.52 + + + + +
+ + EGD701P HEBRIDES + 572125N 0120000W -
565038N 0104118W -
564548N 0100000W -
562630N 0100000W -
570000N 0120000W -
572125N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57.3568694444,30449.52 -12,57,30449.52 -10,56.4417388889,30449.52 -10,56.7633694444,30449.52 -10.6883611111,56.8439194444,30449.52 -12,57.3568694444,30449.52 + + + + +
+ + EGD701Q HEBRIDES + 572125N 0120000W -
571500N 0100000W -
564548N 0100000W -
565038N 0104118W -
572125N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57.3568694444,30449.52 -10.6883611111,56.8439194444,30449.52 -10,56.7633694444,30449.52 -10,57.25,30449.52 -12,57.3568694444,30449.52 + + + + +
+ + EGD701R HEBRIDES + 580135N 0120000W -
573301N 0100000W -
571500N 0100000W -
572125N 0120000W -
580135N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,58.0264222222,30449.52 -12,57.3568694444,30449.52 -10,57.25,30449.52 -10,57.5501444444,30449.52 -12,58.0264222222,30449.52 + + + + +
+ + EGD701S HEBRIDES + 584514N 0120000W -
582859N 0100000W -
573301N 0100000W -
580135N 0120000W -
584514N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,58.7539083333,30449.52 -12,58.0264222222,30449.52 -10,57.5501444444,30449.52 -10,58.4831388889,30449.52 -12,58.7539083333,30449.52 + + + + +
+ + EGD701T HEBRIDES + 593000N 0120000W following the line of latitude to -
593000N 0100000W -
582859N 0100000W -
584514N 0120000W -
593000N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,59.5,30449.52 -12,58.7539083333,30449.52 -10,58.4831388889,30449.52 -10,59.5,30449.52 -10.1666666667,59.5,30449.52 -10.3333333333,59.5,30449.52 -10.5,59.5,30449.52 -10.6666666667,59.5,30449.52 -10.8333333333,59.5,30449.52 -11,59.5,30449.52 -11.1666666667,59.5,30449.52 -11.3333333333,59.5,30449.52 -11.5,59.5,30449.52 -11.6666666667,59.5,30449.52 -11.8333333333,59.5,30449.52 -12,59.5,30449.52 + + + + +
+ + EGD701U HEBRIDES + 590000N 0130000W -
593000N 0120000W -
584514N 0120000W -
585236N 0130000W -
590000N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,59,30449.52 -13,58.8765361111,30449.52 -12,58.7539083333,30449.52 -12,59.5,30449.52 -13,59,30449.52 + + + + +
+ + EGD701V HEBRIDES + 585236N 0130000W -
584514N 0120000W -
580135N 0120000W -
581454N 0130000W -
585236N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,58.8765361111,30449.52 -13,58.2481972222,30449.52 -12,58.0264222222,30449.52 -12,58.7539083333,30449.52 -13,58.8765361111,30449.52 + + + + +
+ + EGD701W HEBRIDES + 581454N 0130000W -
580135N 0120000W -
572125N 0120000W -
573126N 0130000W -
581454N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,58.2481972222,30449.52 -13,57.5239055556,30449.52 -12,57.3568694444,30449.52 -12,58.0264222222,30449.52 -13,58.2481972222,30449.52 + + + + +
+ + EGD701X HEBRIDES + 573126N 0130000W -
572125N 0120000W -
564357N 0120000W -
573126N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,57.5239055556,30449.52 -12,56.7324472222,30449.52 -12,57.3568694444,30449.52 -13,57.5239055556,30449.52 + + + + +
+ + EGD701Y HEBRIDES + 573809N 0073422W -
572324N 0072233W -
572253N 0072531W -
573347N 0074803W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
573809N 0073422W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.572686111099999,57.6358,30449.52 -7.5908058302,57.63250052330001,30449.52 -7.608740671100001,57.6289270654,30449.52 -7.6264459435,57.6250405088,30449.52 -7.643902586399999,57.6208450543,30449.52 -7.6610918269,57.61634523510001,30449.52 -7.677995200800001,57.6115459113,30449.52 -7.6945945737,57.6064522647,30449.52 -7.710872161599999,57.6010697925,30449.52 -7.726810550800001,57.5954043011,30449.52 -7.7423927169,57.58946189949999,30449.52 -7.7576020438,57.58324899199999,30449.52 -7.7724223421,57.5767722714,30449.52 -7.786837866700001,57.5700387107,30449.52 -7.800833333299999,57.5630555556,30449.52 -7.4252777778,57.3813888889,30449.52 -7.3758333333,57.39000000000001,30449.52 -7.572686111099999,57.6358,30449.52 + + + + +
+ + EGD702 FORT GEORGE + 573617N 0040047W -
573449N 0040128W -
573440N 0040257W -
573456N 0040438W -
573534N 0040338W -
573617N 0040047W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Inverness APP/Tower on 122.605 MHz when open; at other times Scottish Information on 134.850 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-108124/108114.

Remarks: SI 1940/30.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0130555556,57.6047222222,640.08 -4.0605555556,57.5927777778,640.08 -4.0772222222,57.5822222222,640.08 -4.0491666667,57.57777777780001,640.08 -4.0244444444,57.5802777778,640.08 -4.0130555556,57.6047222222,640.08 + + + + +
+ + EGD703 TAIN + 575224N 0033030W -
575054N 0034630W -
574500N 0035500W -
574500N 0040254W -
575136N 0040812W -
580324N 0034436W -
580700N 0033700W -
580300N 0033000W -
575224N 0033000W -
575224N 0033030W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 15,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 22,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Para Dropping / Electronic/Optical Hazards.

Service: SUACS: Tain Range on 122.750 MHz when open. SUAAIS: Tain Range on 122.750 MHz when open; at other times Scottish Information on 134.850 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: Aircraft wishing to use Dornoch or Easter Aerodromes during range opening hours are to contact Tain Range on 122.750 MHz prior to entering the range. Associated aircraft operations outside area boundary. SI 1940/684. UAS BVLOS will not be conducted above 2000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5083333333,57.8733333333,6705.599999999999 -3.5,57.8733333333,6705.599999999999 -3.5,58.05,6705.599999999999 -3.6166666667,58.1166666667,6705.599999999999 -3.7433333333,58.0566666667,6705.599999999999 -4.1366666667,57.86,6705.599999999999 -4.0483333333,57.75000000000001,6705.599999999999 -3.9166666667,57.75000000000001,6705.599999999999 -3.775,57.8483333333,6705.599999999999 -3.5083333333,57.8733333333,6705.599999999999 + + + + +
+ + EGD704 HEBRIDES + 573727N 0071811W -
573143N 0071055W -
572625N 0072457W -
573305N 0073017W -
573727N 0071811W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUACS: Benbecula Approach on 119.205 MHz when open. SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.303055555600001,57.6241666667,3048 -7.504722222199999,57.5513888889,3048 -7.4158333333,57.44027777779999,3048 -7.181944444400001,57.52861111110001,3048 -7.303055555600001,57.6241666667,3048 + + + + +
+ + EGD710 RAASAY + 572200N 0054927W -
572200N 0055935W - then along the east coast of Raasay and Rona in an northerly direction to
573500N 0055800W -
573800N 0055800W -
573800N 0055000W -
573445N 0055000W - then along the west coast of the Applecross peninsula in an southerly direction to -
572200N 0054927W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01397-436720.

Remarks: SI 2016/654.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.824166666699999,57.3666666667,457.2 -5.8226555556,57.36760277779999,457.2 -5.8224527778,57.36886666669999,457.2 -5.8234638889,57.3721638889,457.2 -5.8240722222,57.37322499999999,457.2 -5.8225916667,57.3749777778,457.2 -5.8243083333,57.3770833333,457.2 -5.8253972222,57.37795,457.2 -5.8264361111,57.3815166667,457.2 -5.825166666699999,57.38371111110001,457.2 -5.8259833333,57.3867444444,457.2 -5.826611111100001,57.3879833333,457.2 -5.8284305556,57.3894583333,457.2 -5.829925,57.39085,457.2 -5.8288083333,57.39197222220001,457.2 -5.8265416667,57.39130555560001,457.2 -5.8242083333,57.3913027778,457.2 -5.8240833333,57.3894555556,457.2 -5.8210777778,57.3876138889,457.2 -5.818275,57.3894972222,457.2 -5.8188222222,57.3915472222,457.2 -5.8205416667,57.3936527778,457.2 -5.820855555599999,57.3950833333,457.2 -5.818997222200001,57.39801666670001,457.2 -5.8183916667,57.4014888889,457.2 -5.8152333333,57.4009194444,457.2 -5.8142611111,57.399725,457.2 -5.8131638889,57.39783333329999,457.2 -5.8121638889,57.39509444439999,457.2 -5.8105222222,57.3954944444,457.2 -5.8097055556,57.393875,457.2 -5.8080416667,57.3940694444,457.2 -5.8062666667,57.39188333329999,457.2 -5.803124999999999,57.391125,457.2 -5.803124999999999,57.3927444444,457.2 -5.8058944444,57.3953583333,457.2 -5.807980555600001,57.3961916667,457.2 -5.8087861111,57.39913611109999,457.2 -5.8064416667,57.3990277778,457.2 -5.8055472222,57.4000444444,457.2 -5.807688888899999,57.4014166667,457.2 -5.808275,57.4054472222,457.2 -5.8103805556,57.4064611111,457.2 -5.813627777799999,57.4072611111,457.2 -5.815799999999999,57.4105222222,457.2 -5.818783333299999,57.4119611111,457.2 -5.823711111100001,57.4112722222,457.2 -5.8244055556,57.41313888889999,457.2 -5.8238833333,57.4161222222,457.2 -5.8244111111,57.41799444439999,457.2 -5.8238777778,57.41926944439999,457.2 -5.8217138889,57.4224833333,457.2 -5.821116666699999,57.42475,457.2 -5.818416666700001,57.4276194444,457.2 -5.8169944444,57.42838055559999,457.2 -5.8152527778,57.4308611111,457.2 -5.8148944444,57.4322222222,457.2 -5.8130111111,57.4333583333,457.2 -5.8099277778,57.43416944439999,457.2 -5.8050638889,57.43710555560001,457.2 -5.8060277778,57.4399527778,457.2 -5.8101388889,57.4409972222,457.2 -5.8113777778,57.4416805556,457.2 -5.816375,57.44323611110001,457.2 -5.8245111111,57.4412805556,457.2 -5.8296361111,57.4408555556,457.2 -5.8365972222,57.4404638889,457.2 -5.839950000000001,57.44063055560001,457.2 -5.8442444444,57.4402305556,457.2 -5.849816666700001,57.4408694444,457.2 -5.8519055556,57.4417055556,457.2 -5.855736111100001,57.444825,457.2 -5.8582361111,57.44798611110001,457.2 -5.8597777778,57.4515361111,457.2 -5.860766666699999,57.4545638889,457.2 -5.8599416667,57.457825,457.2 -5.860183333300001,57.4616833333,457.2 -5.8628055556,57.4643916667,457.2 -5.8637527778,57.4670611111,457.2 -5.8619277778,57.4687333333,457.2 -5.862116666700001,57.4705277778,457.2 -5.8678166667,57.4691833333,457.2 -5.8704361111,57.4702722222,457.2 -5.871280555599999,57.47510277779999,457.2 -5.867447222199999,57.4798944444,457.2 -5.8674805556,57.48493055560001,457.2 -5.86865,57.4896611111,457.2 -5.866241666699999,57.4921611111,457.2 -5.8660944444,57.49549444440001,457.2 -5.8653222222,57.497675,457.2 -5.8675888889,57.5017416667,457.2 -5.8654861111,57.5071111111,457.2 -5.8640333333,57.50760555560001,457.2 -5.8626361111,57.5101666667,457.2 -5.8615805556,57.514425,457.2 -5.8604861111,57.5167083333,457.2 -5.8572277778,57.520675,457.2 -5.855633333299999,57.5229694444,457.2 -5.8530027778,57.5265583333,457.2 -5.8536611111,57.5312138889,457.2 -5.853575,57.5335555556,457.2 -5.8515055556,57.53928333330001,457.2 -5.8521333333,57.54205,457.2 -5.8519972222,57.54394444439999,457.2 -5.8527805556,57.5497638889,457.2 -5.8457,57.5524083333,457.2 -5.8444638889,57.5549638889,457.2 -5.8476583333,57.5582833333,457.2 -5.8486388889,57.56122222219999,457.2 -5.8474555556,57.56269722219999,457.2 -5.844719444399999,57.56215,457.2 -5.8395916667,57.5595194444,457.2 -5.837630555599999,57.5567916667,457.2 -5.8345305556,57.5591333333,457.2 -5.8343666667,57.5607555556,457.2 -5.8356972222,57.5638638889,457.2 -5.8353916667,57.56890833329999,457.2 -5.8387138889,57.5702444444,457.2 -5.8395444444,57.5733666667,457.2 -5.841044444399999,57.5764694444,457.2 -5.8387083333,57.57654166670001,457.2 -5.8361222222,57.57742777779999,457.2 -5.8333333333,57.5791666667,457.2 -5.8333333333,57.6333333333,457.2 -5.9666666667,57.6333333333,457.2 -5.9666666667,57.5833333333,457.2 -5.9656777778,57.58196388890001,457.2 -5.9642555556,57.5796722222,457.2 -5.960025,57.5807944444,457.2 -5.959869444399999,57.5793611111,457.2 -5.9559944444,57.57912222219999,457.2 -5.9558777778,57.5780472222,457.2 -5.9564777778,57.57586944440001,457.2 -5.9558805556,57.57346111109999,457.2 -5.956099999999999,57.5693166667,457.2 -5.9538444444,57.5685777778,457.2 -5.9538555556,57.5656111111,457.2 -5.9564277778,57.5646305556,457.2 -5.9579111111,57.562875,457.2 -5.956577777800001,57.5613888889,457.2 -5.957716666700001,57.55955277779999,457.2 -5.9601694444,57.55749722220001,457.2 -5.9604083333,57.55506388889999,457.2 -5.9609583333,57.5524388889,457.2 -5.9635583333,57.5517277778,457.2 -5.9653055556,57.5493333333,457.2 -5.9653555556,57.546725,457.2 -5.9635722222,57.5441722222,457.2 -5.9645444444,57.5423444444,457.2 -5.9657694444,57.5413166667,457.2 -5.9664888889,57.5386861111,457.2 -5.9691638889,57.5371611111,457.2 -5.968675000000001,57.5342111111,457.2 -5.9699222222,57.53183333330001,457.2 -5.972283333299999,57.5305,457.2 -5.970030555599999,57.5282333333,457.2 -5.968847222199999,57.5265611111,457.2 -5.9705138889,57.5249805556,457.2 -5.972386111100001,57.5237527778,457.2 -5.9724361111,57.5226694444,457.2 -5.971555555599999,57.5207194444,457.2 -5.9743277778,57.5185638889,457.2 -5.9744472222,57.51658333329999,457.2 -5.975652777800001,57.515375,457.2 -5.975877777800001,57.51285,457.2 -5.976505555599999,57.5109416667,457.2 -5.9816888889,57.5094305556,457.2 -5.985802777800001,57.50885,457.2 -5.9897583333,57.5053083333,457.2 -5.9887194444,57.5034527778,457.2 -5.9866527778,57.5028861111,457.2 -5.9850777778,57.5006888889,457.2 -5.9834805556,57.4998388889,457.2 -5.983375,57.497325,457.2 -5.980113888899999,57.49499999999999,457.2 -5.9782555556,57.4932611111,457.2 -5.9807222222,57.4913833333,457.2 -5.9810944444,57.4902027778,457.2 -5.9808805556,57.4882305556,457.2 -5.9821027778,57.485675,457.2 -5.983152777799999,57.48456388889999,457.2 -5.983172222200001,57.4816833333,457.2 -5.983788888899999,57.4796861111,457.2 -5.9864222222,57.4778055556,457.2 -5.9860888889,57.4762861111,457.2 -5.987175,57.4740027778,457.2 -5.990150000000001,57.4706722222,457.2 -5.9904444444,57.468775,457.2 -5.9925472222,57.46511111109999,457.2 -5.9954416667,57.4610611111,457.2 -5.9973111111,57.4583055556,457.2 -5.999336111099999,57.45698055559999,457.2 -5.9996277778,57.4550833333,457.2 -6.0013388889,57.45395000000001,457.2 -6.0022861111,57.4519416667,457.2 -6.004125000000001,57.4504444444,457.2 -6.0071361111,57.4505277778,457.2 -6.009052777800001,57.4497472222,457.2 -6.0092,57.4480333333,457.2 -6.0119472222,57.4472277778,457.2 -6.0136555556,57.4445638889,457.2 -6.02005,57.44355277780001,457.2 -6.0248194444,57.4414222222,457.2 -6.0272611111,57.4378361111,457.2 -6.0312361111,57.43456111110001,457.2 -6.0318694444,57.4327416667,457.2 -6.0310027778,57.4279138889,457.2 -6.0259861111,57.4232166667,457.2 -6.0235111111,57.41888888890001,457.2 -6.022061111100001,57.4163277778,457.2 -6.020047222200001,57.41162777779999,457.2 -6.0197805556,57.4092083333,457.2 -6.0189972222,57.40662499999999,457.2 -6.01925,57.4043666667,457.2 -6.0186805556,57.40070000000001,457.2 -6.0175166667,57.39767777779999,457.2 -6.0179166667,57.3952388889,457.2 -6.0181277778,57.3895638889,457.2 -6.01465,57.3851805556,457.2 -6.0129305556,57.3831666667,457.2 -6.010194444399999,57.3794777778,457.2 -6.0056472222,57.3759333333,457.2 -6.002922222199999,57.3738638889,457.2 -6.001108333300001,57.3709527778,457.2 -5.997458333299999,57.3695388889,457.2 -5.994930555600001,57.3707888889,457.2 -5.9935638889,57.37047222219999,457.2 -5.9927944444,57.3679805556,457.2 -5.9930555556,57.3666666667,457.2 -5.824166666699999,57.3666666667,457.2 + + + + +
+ + EGD712A NORTHERN COMPLEX + 585202N 0052659W -
581310N 0052344W -
581920N 0055243W -
584432N 0055510W -
585202N 0052659W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,20116.8 -5.9194527778,58.7421972222,20116.8 -5.8786277778,58.3221666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.9194527778,58.7421972222,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.8786277778,58.3221666667,20116.8 -5.9194527778,58.7421972222,20116.8 -5.9194527778,58.7421972222,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.8786277778,58.3221666667,20116.8 -5.8786277778,58.3221666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + +
+ + EGD712B NORTHERN COMPLEX + 591444N 0035801W -
590716N 0033308W -
580412N 0044247W -
581310N 0052344W -
585202N 0052659W -
591444N 0035801W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,20116.8 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.9668944444,59.2454388889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -3.9668944444,59.2454388889,20116.8 -3.9668944444,59.2454388889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 -3.9668944444,59.2454388889,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + +
+ + EGD712C NORTHERN COMPLEX + 590716N 0033308W -
584654N 0022720W -
574827N 0033350W -
580412N 0044247W -
590716N 0033308W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -3.552325,59.1212277778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + +
+ + EGD712D NORTHERN COMPLEX + 584654N 0022720W -
583622N 0015427W -
574000N 0020624W following the line of latitude to -
574000N 0025821W -
574827N 0033350W -
584654N 0022720W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -2.972480555599999,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.1065472222,57.6666666667,20116.8 -1.907375,58.6059777778,20116.8 -2.4555083333,58.7817138889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -2.972480555599999,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.5638888889,57.8074444444,7467.6 -2.972480555599999,57.6666666667,7467.6 -2.972480555599999,57.6666666667,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.972480555599999,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.8281583333,57.6666666667,20116.8 -2.972480555599999,57.6666666667,20116.8 -2.972480555599999,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.6838361111,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.8281583333,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.5395138889,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.6838361111,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.3951916667,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.5395138889,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.2508694444,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.3951916667,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -2.1065472222,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.2508694444,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -1.907375,58.6059777778,20116.8 -2.1065472222,57.6666666667,20116.8 -2.1065472222,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -1.907375,58.6059777778,20116.8 -1.907375,58.6059777778,7467.6 + + + + + +
+ + EGD713 FAST JET AREA SOUTH + 575900N 0065200W -
574600N 0061000W -
563500N 0052200W -
560600N 0063000W -
561000N 0065400W -
564200N 0081500W -
575000N 0081500W -
575900N 0065200W
Upper limit: FL550
Lower limit: FL245
Class: AMC: Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.

Danger Area Authority: HQ Air.

EGD713 is solely in support of Ex Joint Warrior.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,16764 -8.25,57.8333333333,16764 -8.25,56.7,16764 -6.9,56.1666666667,16764 -6.499999999999999,56.09999999999999,16764 -5.3666666667,56.5833333333,16764 -6.1666666667,57.7666666667,16764 -6.8666666667,57.9833333333,16764 + + + + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.499999999999999,56.09999999999999,7467.6 -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,57.8333333333,16764 -6.8666666667,57.9833333333,16764 -6.8666666667,57.9833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -8.25,56.7,16764 -8.25,57.8333333333,16764 -8.25,57.8333333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.9,56.1666666667,16764 -8.25,56.7,16764 -8.25,56.7,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.9,56.1666666667,7467.6 -6.499999999999999,56.09999999999999,7467.6 -6.499999999999999,56.09999999999999,16764 -6.9,56.1666666667,16764 -6.9,56.1666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.499999999999999,56.09999999999999,7467.6 -5.3666666667,56.5833333333,7467.6 -5.3666666667,56.5833333333,16764 -6.499999999999999,56.09999999999999,16764 -6.499999999999999,56.09999999999999,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.1666666667,57.7666666667,16764 -5.3666666667,56.5833333333,16764 -5.3666666667,56.5833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 -6.8666666667,57.9833333333,16764 -6.1666666667,57.7666666667,16764 -6.1666666667,57.7666666667,7467.6 + + + + + +
+ + EGD801 CAPE WRATH (NORTH WEST) + 590000N 0043000W -
584500N 0043000W following the line of latitude to -
584500N 0050000W -
590000N 0050000W following the line of latitude to -
590000N 0043000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: SI 1933/40.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5,59,16764 -4.6666666667,59,16764 -4.8333333333,59,16764 -5,59,16764 -5,58.75,16764 -4.8333333333,58.75,16764 -4.6666666667,58.75,16764 -4.5,58.75,16764 -4.5,59,16764 + + + + +
+ + EGD802 CAPE WRATH (SOUTH EAST) + 584500N 0043000W -
583435N 0043000W - then along the coastline to
583200N 0044728W -
583200N 0050000W -
584500N 0050000W -
584500N 0043000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: SI 1933/40.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5,58.75,16764 -5,58.75,16764 -5,58.5333333333,16764 -4.7911111111,58.5333333333,16764 -4.7888388889,58.5339416667,16764 -4.7865,58.53695833330001,16764 -4.7850277778,58.5378888889,16764 -4.7821583333,58.53858055559999,16764 -4.7800055556,58.54177222220001,16764 -4.7775861111,58.54595833330001,16764 -4.7768333333,58.5516388889,16764 -4.7810527778,58.5528055556,16764 -4.7883194444,58.5533666667,16764 -4.7911638889,58.5545611111,16764 -4.7964083333,58.5577722222,16764 -4.7979111111,58.5593583333,16764 -4.8025111111,58.5609666667,16764 -4.8052416667,58.56288333330001,16764 -4.8051638889,58.5640527778,16764 -4.8023027778,58.5669916667,16764 -4.7998861111,58.5690222222,16764 -4.7968361111,58.57178333329999,16764 -4.7967944444,58.57340277780001,16764 -4.7955055556,58.57666666669999,16764 -4.7934305556,58.5765305556,16764 -4.7921222222,58.5773694444,16764 -4.7896722222,58.5768833333,16764 -4.7874611111,58.5772,16764 -4.7850138889,58.5767138889,16764 -4.7835194444,58.577375,16764 -4.7754583333,58.5777305556,16764 -4.7714388889,58.57691666669999,16764 -4.7660694444,58.57649444439999,16764 -4.7634555556,58.5804138889,16764 -4.7632,58.5837444444,16764 -4.7669722222,58.5857305556,16764 -4.7716444444,58.5903944444,16764 -4.7741055556,58.5910583333,16764 -4.7765527778,58.5937027778,16764 -4.7847944444,58.5955916667,16764 -4.7883027778,58.5985694444,16764 -4.7902638889,58.5994277778,16764 -4.7905138889,58.6004083333,16764 -4.7868416667,58.5996805556,16764 -4.7832805556,58.6003861111,16764 -4.7772444444,58.6002472222,16764 -4.7743861111,58.603275,16764 -4.7684472222,58.6043916667,16764 -4.7687055556,58.6033083333,16764 -4.7699444444,58.601575,16764 -4.7695083333,58.6004138889,16764 -4.7655805556,58.5986111111,16764 -4.7646277778,58.5974638889,16764 -4.7666861111,58.5951722222,16764 -4.7654555556,58.5926833333,16764 -4.7653222222,58.5909777778,16764 -4.7623583333,58.5883472222,16764 -4.7578777778,58.5882638889,16764 -4.7567666667,58.5894555556,16764 -4.7544055556,58.5878888889,16764 -4.7537694444,58.586375,16764 -4.7526916667,58.5836111111,16764 -4.7491583333,58.5824277778,16764 -4.7442472222,58.5834333333,16764 -4.741725,58.58420555560001,16764 -4.7414416667,58.58277222219999,16764 -4.7396111111,58.58137500000001,16764 -4.7406972222,58.5776666667,16764 -4.7425333333,58.5747527778,16764 -4.7409388889,58.5741583333,16764 -4.7406472222,58.5726361111,16764 -4.7386916667,58.5696222222,16764 -4.7324305556,58.5665194444,16764 -4.729175,58.5666777778,16764 -4.7267027778,58.5680805556,16764 -4.7254333333,58.56945555559999,16764 -4.7205027778,58.5701888889,16764 -4.7173277778,58.56917777779999,16764 -4.7176888889,58.5671916667,16764 -4.7182972222,58.5639444444,16764 -4.7163972222,58.56605,16764 -4.7141944444,58.56870277780001,16764 -4.7092666667,58.5672805556,16764 -4.7046722222,58.5656694444,16764 -4.70695,58.5640027778,16764 -4.7093138889,58.5634138889,16764 -4.7096194444,58.5607111111,16764 -4.704125,58.5585805556,16764 -4.7022972222,58.55718333330001,16764 -4.6996666667,58.5565194444,16764 -4.6955333333,58.556425,16764 -4.6915916667,58.55659722219999,16764 -4.6897777778,58.5553777778,16764 -4.6859944444,58.5553666667,16764 -4.6826361111,58.5541805556,16764 -4.6787833333,58.5532722222,16764 -4.6781583333,58.5518472222,16764 -4.6789222222,58.5505722222,16764 -4.6741638889,58.54905555560001,16764 -4.6741,58.5504944444,16764 -4.6698444444,58.55103055559999,16764 -4.6644805556,58.5506027778,16764 -4.6621944444,58.5521777778,16764 -4.6593666667,58.55115833329999,16764 -4.65495,58.5518805556,16764 -4.6533166667,58.5507444444,16764 -4.6577416667,58.5478666667,16764 -4.6579833333,58.54651388889999,16764 -4.6575111111,58.54481666670001,16764 -4.6549027778,58.54442222219999,16764 -4.6536194444,58.5433694444,16764 -4.6541222222,58.5409333333,16764 -4.6516722222,58.54035555559999,16764 -4.6519083333,58.5389111111,16764 -4.6504388889,58.5376833333,16764 -4.6507305556,58.5347111111,16764 -4.6525638889,58.5339555556,16764 -4.6531222222,58.53223611109999,16764 -4.6598416667,58.5279638889,16764 -4.6617027778,58.5253194444,16764 -4.6653138889,58.5253333333,16764 -4.6672888889,58.5264611111,16764 -4.6697861111,58.5254222222,16764 -4.6733083333,58.52202222219999,16764 -4.6764222222,58.5200694444,16764 -4.6799694444,58.5170305556,16764 -4.6825277778,58.51455,16764 -4.6842916667,58.51289722220001,16764 -4.6871722222,58.5123861111,16764 -4.6932972222,58.5093833333,16764 -4.6931583333,58.5053416667,16764 -4.6987944444,58.5027055556,16764 -4.7025694444,58.5004694444,16764 -4.7072583333,58.4989333333,16764 -4.7100555556,58.49734722219999,16764 -4.7121166667,58.4951472222,16764 -4.7145194444,58.4906916667,16764 -4.7170527778,58.4879416667,16764 -4.71765,58.48676111110001,16764 -4.7203805556,58.4843666667,16764 -4.7222277778,58.4816333333,16764 -4.7251944444,58.4800416667,16764 -4.7267472222,58.4779416667,16764 -4.7280861111,58.4753055556,16764 -4.7307222222,58.4739027778,16764 -4.7344666667,58.4713055556,16764 -4.7383333333,58.4680777778,16764 -4.7385833333,58.46690555560001,16764 -4.7443222222,58.4628361111,16764 -4.7441861111,58.4611055556,16764 -4.7425361111,58.45819166670001,16764 -4.7486472222,58.45958888889999,16764 -4.7506277778,58.45640277779999,16764 -4.7488222222,58.453025,16764 -4.7537166667,58.4507194444,16764 -4.7582972222,58.4492277778,16764 -4.7553166667,58.44839166669999,16764 -4.7476916667,58.4495444444,16764 -4.7484138889,58.4478222222,16764 -4.7491083333,58.4457388889,16764 -4.7467416667,58.44615,16764 -4.7428833333,58.4472222222,16764 -4.7409277778,58.4485222222,16764 -4.7356666667,58.4470166667,16764 -4.7324972222,58.4481611111,16764 -4.7285888889,58.45300833329999,16764 -4.7243194444,58.4576833333,16764 -4.7244527778,58.4593861111,16764 -4.7213472222,58.4635861111,16764 -4.7148,58.4631861111,16764 -4.7119722222,58.464325,16764 -4.7069027778,58.4653305556,16764 -4.7046027778,58.4666388889,16764 -4.6980888889,58.4689305556,16764 -4.694775,58.4726861111,16764 -4.6944527778,58.4752083333,16764 -4.6932833333,58.47783888890001,16764 -4.6876361111,58.4780472222,16764 -4.6836555556,58.47759166670001,16764 -4.6808611111,58.4791777778,16764 -4.6776333333,58.4818527778,16764 -4.6717666667,58.4836805556,16764 -4.6679,58.4825055556,16764 -4.6630916667,58.482425,16764 -4.661025,58.484625,16764 -4.6605111111,58.4868805556,16764 -4.6614888889,58.490725,16764 -4.6605,58.4935305556,16764 -4.660675,58.4958638889,16764 -4.6616055556,58.4968333333,16764 -4.6608916667,58.4987361111,16764 -4.6589833333,58.503,16764 -4.6583972222,58.5066055556,16764 -4.6556472222,58.5088194444,16764 -4.6511444444,58.5106194444,16764 -4.6507194444,58.5117972222,16764 -4.6481305556,58.51391666670001,16764 -4.6474027778,58.51563888890001,16764 -4.6442583333,58.5172333333,16764 -4.6433722222,58.5191388889,16764 -4.6405694444,58.5207222222,16764 -4.6376222222,58.5203333333,16764 -4.6324277778,58.5198111111,16764 -4.6274388889,58.52198055560001,16764 -4.6224472222,58.52415,16764 -4.6163972222,58.5236444444,16764 -4.6169472222,58.52183611110001,16764 -4.6151722222,58.5210638889,16764 -4.6144638889,58.5184722222,16764 -4.6153722222,58.51683611110001,16764 -4.6153833333,58.5146777778,16764 -4.6192472222,58.5135222222,16764 -4.6205527778,58.51259722220001,16764 -4.6184944444,58.5073277778,16764 -4.61745,58.50780833329999,16764 -4.6179666667,58.5101333333,16764 -4.6177833333,58.51229444440001,16764 -4.6135638889,58.5132777778,16764 -4.6115083333,58.51565555559999,16764 -4.6108388889,58.52052222219999,16764 -4.6076555556,58.5239138889,16764 -4.6025166667,58.52644444439999,16764 -4.5996138889,58.52668055560001,16764 -4.59945,58.5291111111,16764 -4.5989638889,58.5318166667,16764 -4.5949833333,58.5337833333,16764 -4.5909666667,58.5352138889,16764 -4.59195,58.5369,16764 -4.5906833333,58.5407,16764 -4.591675,58.54481388890001,16764 -4.5941777778,58.54845,16764 -4.6008472222,58.5526277778,16764 -4.6020444444,58.55485,16764 -4.5994,58.5585861111,16764 -4.594725,58.5604805556,16764 -4.5946861111,58.5622777778,16764 -4.5930805556,58.5638361111,16764 -4.5935638889,58.5657138889,16764 -4.5960277778,58.566475,16764 -4.594225,58.56767777779999,16764 -4.597375,58.5684222222,16764 -4.5973111111,58.5698638889,16764 -4.5962222222,58.5714111111,16764 -4.5939083333,58.5727166667,16764 -4.5908972222,58.5738555556,16764 -4.5868611111,58.5751055556,16764 -4.5901583333,58.5754888889,16764 -4.58805,58.5772388889,16764 -4.5841194444,58.5775861111,16764 -4.5809138889,58.5784611111,16764 -4.5794527778,58.5796583333,16764 -4.5767638889,58.5805194444,16764 -4.5751444444,58.57956388889999,16764 -4.570575,58.5758833333,16764 -4.5684527778,58.5751166667,16764 -4.5652805556,58.5764361111,16764 -4.561925,58.5775833333,16764 -4.55375,58.5763972222,16764 -4.5515166667,58.57644166670001,16764 -4.5434027778,58.57840000000001,16764 -4.5442333333,58.5803611111,16764 -4.5396555556,58.5789222222,16764 -4.53655,58.5788055556,16764 -4.5354166667,58.5798166667,16764 -4.5332722222,58.5786888889,16764 -4.5269027778,58.57863611110001,16764 -4.5256972222,58.5762333333,16764 -4.5235944444,58.5757361111,16764 -4.52175,58.5764,16764 -4.5173805556,58.5778333333,16764 -4.5143138889,58.5782527778,16764 -4.51075,58.576525,16764 -4.506925,58.5759722222,16764 -4.5025916667,58.5755166667,16764 -4.5,58.57638888890001,16764 -4.5,58.75,16764 + + + + +
+ + EGD803 GARVIE ISLAND + A circle, 4 NM radius, centred at 583705N 0045220W
Upper limit: 40000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8722222222,58.6845611849,12192 -4.8815454206,58.6843834303,12192 -4.8908185925,58.6838511206,12192 -4.8999919843,58.6829671118,12192 -4.909016387,58.6817361468,12192 -4.9178434039,58.6801648294,12192 -4.9264257149,58.6782615883,12192 -4.9347173328,58.6760366312,12192 -4.9426738539,58.67350188899999,12192 -4.9502526977,58.67067095120001,12192 -4.9574133368,58.66755899179999,12192 -4.9641175159,58.66418268660001,12192 -4.9703294558,58.66056012310001,12192 -4.9760160454,58.6567107024,12192 -4.981147017,58.6526550338,12192 -4.9856951069,58.6484148234,12192 -4.9896361975,58.6440127571,12192 -4.9929494437,58.6394723782,12192 -4.9956173795,58.63481796029999,12192 -4.9976260072,58.6300743768,12192 -4.9989648664,58.6252669678,12192 -4.9996270849,58.62042140359999,12192 -4.9996094092,58.6155635479,12192 -4.9989122161,58.610719319,12192 -4.9975395044,58.6059145521,12192 -4.9954988679,58.6011748612,12192 -4.992801449,58.59652550329999,12192 -4.9894618741,58.5919912442,12192 -4.98549817,58.58759622699999,12192 -4.9809316641,58.58336384460001,12192 -4.9757868662,58.57931661620001,12192 -4.9700913349,58.57547606800001,12192 -4.9638755284,58.5718626203,12192 -4.9571726403,58.5684954797,12192 -4.9500184221,58.56539253839999,12192 -4.9424509926,58.5625702802,12192 -4.9345106356,58.560043694,12192 -4.9262395872,58.5578261953,12192 -4.9176818128,58.55592955629999,12192 -4.9088827764,58.55436384389999,12192 -4.8998892021,58.5531373672,12192 -4.8907488293,58.5522566345,12192 -4.8815101633,58.5517263187,12192 -4.8722222222,58.5515492336,12192 -4.8629342812,58.5517263187,12192 -4.8536956152,58.5522566345,12192 -4.8445552423,58.5531373672,12192 -4.835561668,58.55436384389999,12192 -4.8267626317,58.55592955629999,12192 -4.8182048573,58.5578261953,12192 -4.8099338088,58.560043694,12192 -4.8019934519,58.5625702802,12192 -4.7944260223,58.56539253839999,12192 -4.7872718041,58.5684954797,12192 -4.780568916,58.5718626203,12192 -4.7743531095,58.57547606800001,12192 -4.7686575783,58.57931661620001,12192 -4.7635127804,58.58336384460001,12192 -4.7589462744,58.58759622699999,12192 -4.7549825704,58.5919912442,12192 -4.7516429954,58.59652550329999,12192 -4.7489455766,58.6011748612,12192 -4.7469049401,58.6059145521,12192 -4.7455322283,58.610719319,12192 -4.7448350352,58.6155635479,12192 -4.7448173595,58.62042140359999,12192 -4.745479578,58.6252669678,12192 -4.7468184373,58.6300743768,12192 -4.7488270649,58.63481796029999,12192 -4.7514950008,58.6394723782,12192 -4.7548082469,58.6440127571,12192 -4.7587493376,58.6484148234,12192 -4.7632974274,58.6526550338,12192 -4.7684283991,58.6567107024,12192 -4.7741149886,58.66056012310001,12192 -4.7803269286,58.66418268660001,12192 -4.7870311076,58.66755899179999,12192 -4.7941917468,58.67067095120001,12192 -4.8017705905,58.67350188899999,12192 -4.8097271116,58.6760366312,12192 -4.8180187296,58.6782615883,12192 -4.8266010405,58.6801648294,12192 -4.8354280575,58.6817361468,12192 -4.8444524601,58.6829671118,12192 -4.853625852,58.6838511206,12192 -4.8628990238,58.6843834303,12192 -4.8722222222,58.6845611849,12192 + + + + +
+ + EGD809C MORAY FIRTH (CENTRAL) + 585000N 0023314W following the line of latitude to -
585000N 0014526W -
582600N 0015049W following the line of latitude to -
582600N 0024048W -
585000N 0023314W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5538888889,58.8333333333,16764 -2.68,58.4333333333,16764 -2.5133888889,58.4333333333,16764 -2.3467777778,58.4333333333,16764 -2.1801666667,58.4333333333,16764 -2.0135555556,58.4333333333,16764 -1.8469444444,58.4333333333,16764 -1.7572222222,58.8333333333,16764 -1.9165555556,58.8333333333,16764 -2.0758888889,58.8333333333,16764 -2.2352222222,58.8333333333,16764 -2.3945555556,58.8333333333,16764 -2.5538888889,58.8333333333,16764 + + + + +
+ + EGD809N MORAY FIRTH (NORTH) + 592300N 0015130W following the line of latitude to -
592300N 0014200W -
590500N 0014200W -
585000N 0014526W following the line of latitude to -
585000N 0023314W -
585800N 0023040W -
592300N 0015130W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8583333333,59.3833333333,16764 -2.5111111111,58.9666666667,16764 -2.5538888889,58.8333333333,16764 -2.3945555556,58.8333333333,16764 -2.2352222222,58.8333333333,16764 -2.0758888889,58.8333333333,16764 -1.9165555556,58.8333333333,16764 -1.7572222222,58.8333333333,16764 -1.7,59.0833333333,16764 -1.7,59.3833333333,16764 -1.8583333333,59.3833333333,16764 + + + + +
+ + EGD809S MORAY FIRTH (SOUTH) + 582600N 0024048W following the line of latitude to -
582600N 0015049W -
575000N 0015840W following the line of latitude to -
575000N 0022415W -
581630N 0024345W -
582600N 0024048W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.68,58.4333333333,16764 -2.7291666667,58.275,16764 -2.4041666667,57.8333333333,16764 -2.262037037,57.8333333333,16764 -2.1199074074,57.8333333333,16764 -1.9777777778,57.8333333333,16764 -1.8469444444,58.4333333333,16764 -2.0135555556,58.4333333333,16764 -2.1801666667,58.4333333333,16764 -2.3467777778,58.4333333333,16764 -2.5133888889,58.4333333333,16764 -2.68,58.4333333333,16764 + + + + +
+ + EGD901 FAST JET AREA NORTH + 594000N 0013000W -
591000N 0010000W -
580215N 0000948E -
574700N 0010000W -
574000N 0013100W following the line of latitude to -
574000N 0025821W -
581920N 0055243W -
595000N 0060149W -
594000N 0013000W
Upper limit: FL550
Lower limit: FL245
Class: AMC: Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.

Danger Area Authority: HQ Air.

EGD901 is solely in support of Ex Joint Warrior.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,16764 -6.030277777799999,59.8333333333,16764 -5.878611111100001,58.3222222222,16764 -2.9725,57.6666666667,16764 -2.8107407407,57.6666666667,16764 -2.6489814815,57.6666666667,16764 -2.4872222222,57.6666666667,16764 -2.325462963,57.6666666667,16764 -2.1637037037,57.6666666667,16764 -2.0019444444,57.6666666667,16764 -1.8401851852,57.6666666667,16764 -1.6784259259,57.6666666667,16764 -1.5166666667,57.6666666667,16764 -1,57.7833333333,16764 0.1633333333,58.0375,16764 -1,59.1666666667,16764 -1.5,59.6666666667,16764 + + + + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,7467.6 -6.030277777799999,59.8333333333,7467.6 -5.878611111100001,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 -1,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,7467.6 -6.030277777799999,59.8333333333,7467.6 -6.030277777799999,59.8333333333,16764 -1.5,59.6666666667,16764 -1.5,59.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.030277777799999,59.8333333333,7467.6 -5.878611111100001,58.3222222222,7467.6 -5.878611111100001,58.3222222222,16764 -6.030277777799999,59.8333333333,16764 -6.030277777799999,59.8333333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.878611111100001,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.9725,57.6666666667,16764 -5.878611111100001,58.3222222222,16764 -5.878611111100001,58.3222222222,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.8107407407,57.6666666667,16764 -2.9725,57.6666666667,16764 -2.9725,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.6489814815,57.6666666667,16764 -2.8107407407,57.6666666667,16764 -2.8107407407,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.4872222222,57.6666666667,16764 -2.6489814815,57.6666666667,16764 -2.6489814815,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.325462963,57.6666666667,16764 -2.4872222222,57.6666666667,16764 -2.4872222222,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.1637037037,57.6666666667,16764 -2.325462963,57.6666666667,16764 -2.325462963,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -2.0019444444,57.6666666667,16764 -2.1637037037,57.6666666667,16764 -2.1637037037,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.8401851852,57.6666666667,16764 -2.0019444444,57.6666666667,16764 -2.0019444444,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.6784259259,57.6666666667,16764 -1.8401851852,57.6666666667,16764 -1.8401851852,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1.5166666667,57.6666666667,16764 -1.6784259259,57.6666666667,16764 -1.6784259259,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.5166666667,57.6666666667,7467.6 -1,57.7833333333,7467.6 -1,57.7833333333,16764 -1.5166666667,57.6666666667,16764 -1.5166666667,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 0.1633333333,58.0375,16764 -1,57.7833333333,16764 -1,57.7833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + 0.1633333333,58.0375,7467.6 -1,59.1666666667,7467.6 -1,59.1666666667,16764 0.1633333333,58.0375,16764 0.1633333333,58.0375,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 -1.5,59.6666666667,16764 -1,59.1666666667,16764 -1,59.1666666667,7467.6 + + + + + +
+
+ + Prohibited + + EGP611 COULPORT / FASLANE + A circle, 2 NM radius, centred at 560331N 0045159W
Upper limit: 2200 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8663888889,56.0918776254,670.5600000000001 -4.8725074402,56.0917011577,670.5600000000001 -4.878560967,56.0911736299,670.5600000000001 -4.8844851413,56.0903006481,670.5600000000001 -4.8902170197,56.089091489,670.5600000000001 -4.8956957176,56.0875590008,670.5600000000001 -4.9008630591,56.0857194653,670.5600000000001 -4.9056641986,56.0835924241,670.5600000000001 -4.9100482046,56.0812004696,670.5600000000001 -4.9139686016,56.0785690036,670.5600000000001 -4.9173838627,56.0757259658,670.5600000000001 -4.9202578484,56.07270153620001,670.5600000000001 -4.9225601874,56.069527813,670.5600000000001 -4.9242665941,56.0662384706,670.5600000000001 -4.9253591212,56.06286840180001,670.5600000000001 -4.9258263439,56.0594533465,670.5600000000001 -4.9256634744,56.056029512,670.5600000000001 -4.9248724057,56.05263318939999,670.5600000000001 -4.9234616844,56.0493003688,670.5600000000001 -4.9214464135,56.04606635790001,670.5600000000001 -4.9188480857,56.0429654094,670.5600000000001 -4.9156943503,56.04003035829999,670.5600000000001 -4.9120187157,56.0372922762,670.5600000000001 -4.9078601907,56.0347801428,670.5600000000001 -4.9032628694,56.03252054120001,670.5600000000001 -4.8982754627,56.03053737780001,670.5600000000001 -4.8929507836,56.0288516311,670.5600000000001 -4.887345189,56.0274811305,670.5600000000001 -4.8815179867,56.02644037000001,670.5600000000001 -4.8755308106,56.0257403549,670.5600000000001 -4.8694469739,56.0253884872,670.5600000000001 -4.8633308039,56.0253884872,670.5600000000001 -4.8572469672,56.0257403549,670.5600000000001 -4.8512597911,56.02644037000001,670.5600000000001 -4.8454325887,56.0274811305,670.5600000000001 -4.8398269942,56.0288516311,670.5600000000001 -4.8345023151,56.03053737780001,670.5600000000001 -4.8295149084,56.03252054120001,670.5600000000001 -4.824917587,56.0347801428,670.5600000000001 -4.8207590621,56.0372922762,670.5600000000001 -4.8170834275,56.04003035829999,670.5600000000001 -4.8139296921,56.0429654094,670.5600000000001 -4.8113313643,56.04606635790001,670.5600000000001 -4.8093160933,56.0493003688,670.5600000000001 -4.8079053721,56.05263318939999,670.5600000000001 -4.8071143034,56.056029512,670.5600000000001 -4.8069514339,56.0594533465,670.5600000000001 -4.8074186566,56.06286840180001,670.5600000000001 -4.8085111837,56.0662384706,670.5600000000001 -4.8102175904,56.069527813,670.5600000000001 -4.8125199293,56.07270153620001,670.5600000000001 -4.8153939151,56.0757259658,670.5600000000001 -4.8188091761,56.0785690036,670.5600000000001 -4.8227295731,56.0812004696,670.5600000000001 -4.8271135792,56.0835924241,670.5600000000001 -4.8319147186,56.0857194653,670.5600000000001 -4.8370820602,56.0875590008,670.5600000000001 -4.8425607581,56.089091489,670.5600000000001 -4.8482926365,56.0903006481,670.5600000000001 -4.8542168107,56.0911736299,670.5600000000001 -4.8602703376,56.0917011577,670.5600000000001 -4.8663888889,56.0918776254,670.5600000000001 + + + + +
+ + EGP813 DOUNREAY + A circle, 2 NM radius, centred at 583435N 0034434W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.7427777778,58.609642007,640.08 -3.7493300434,58.609465595,640.08 -3.755812657199999,58.6089382341,640.08 -3.7621567139,58.6080655301,640.08 -3.7682947936,58.6068567592,640.08 -3.7741616829,58.6053247684,640.08 -3.7796950733,58.6034858381,640.08 -3.7848362261,58.60135950790001,640.08 -3.7895305989,58.5989683673,640.08 -3.7937284254,58.59633781390001,640.08 -3.7973852435,58.5934957828,640.08 -3.8004623645,58.5904724474,640.08 -3.8029272805,58.58729989820001,640.08 -3.8047540042,58.5840118007,640.08 -3.8059233382,58.58064303679999,640.08 -3.8064230716,58.5772293343,640.08 -3.8062481016,58.57380688690001,640.08 -3.805400479199999,58.57041197070001,640.08 -3.8038893795,58.5670805596,640.08 -3.8017309962,58.5638479444,640.08 -3.7989483623,58.56074835999999,640.08 -3.7955710999,58.5578146233,640.08 -3.7916351009,58.55507778770001,640.08 -3.7871821421,58.5525668152,640.08 -3.7822594409,58.5503082721,640.08 -3.7769191536,58.5483260487,640.08 -3.7712178237,58.5466411091,640.08 -3.7652157856,58.5452712702,640.08 -3.758976528799999,58.5442310155,640.08 -3.7525660311,58.5435313422,640.08 -3.7460520656,58.5431796467,640.08 -3.7395034899,58.5431796467,640.08 -3.7329895244,58.5435313422,640.08 -3.7265790268,58.5442310155,640.08 -3.720339769999999,58.5452712702,640.08 -3.7143377318,58.5466411091,640.08 -3.708636402,58.5483260487,640.08 -3.7032961146,58.5503082721,640.08 -3.6983734134,58.5525668152,640.08 -3.6939204547,58.55507778770001,640.08 -3.6899844556,58.5578146233,640.08 -3.6866071933,58.56074835999999,640.08 -3.6838245594,58.5638479444,640.08 -3.681666176,58.5670805596,640.08 -3.6801550763,58.57041197070001,640.08 -3.679307454,58.57380688690001,640.08 -3.679132483900001,58.5772293343,640.08 -3.6796322173,58.58064303679999,640.08 -3.6808015513,58.5840118007,640.08 -3.682628275,58.58729989820001,640.08 -3.6850931911,58.5904724474,640.08 -3.6881703121,58.5934957828,640.08 -3.691827130100001,58.59633781390001,640.08 -3.6960249567,58.5989683673,640.08 -3.7007193295,58.60135950790001,640.08 -3.705860482299999,58.6034858381,640.08 -3.7113938727,58.6053247684,640.08 -3.717260762,58.6068567592,640.08 -3.7233988416,58.6080655301,640.08 -3.7297428984,58.6089382341,640.08 -3.7362255122,58.609465595,640.08 -3.7427777778,58.609642007,640.08 + + + + +
+
+ + Restricted + + EGR002 DEVONPORT + A circle, 1 NM radius, centred at 502317N 0041114W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by helicopter for the purpose of landing or taking off from Kinterbury Point (KP) Helicopter Landing Site (HLS) and Ships within HM Naval Base with the permission of FOST / Plymouth Military Radar and in accordance with any conditions to which permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1872222222,50.40470473780001,609.6 -4.1910152222,50.404527252,609.6 -4.1947272975,50.4039985814,609.6 -4.1982792553,50.403130005,609.6 -4.201595329,50.4019400528,609.6 -4.2046047982,50.4004541095,609.6 -4.2072435002,50.3987038712,609.6 -4.2094551986,50.3967266679,609.6 -4.2111927823,50.3945646657,609.6 -4.2124192668,50.3922639654,609.6 -4.2131085786,50.38987361900001,609.6 -4.2132461049,50.38744458189999,609.6 -4.2128289986,50.38502862690001,609.6 -4.211866232,50.38267724,609.6 -4.2103783981,50.3804405238,609.6 -4.2083972659,50.3783661309,609.6 -4.2059650983,50.37649824940001,609.6 -4.203133748,50.3748766639,609.6 -4.1999635509,50.373535909,609.6 -4.1965220414,50.372504536,609.6 -4.1928825154,50.3718045064,609.6 -4.1891224728,50.3714507253,609.6 -4.1853219717,50.3714507253,609.6 -4.1815619291,50.3718045064,609.6 -4.177922403,50.372504536,609.6 -4.1744808935,50.373535909,609.6 -4.1713106965,50.3748766639,609.6 -4.1684793461,50.37649824940001,609.6 -4.1660471786,50.3783661309,609.6 -4.1640660464,50.3804405238,609.6 -4.1625782125,50.38267724,609.6 -4.1616154458,50.38502862690001,609.6 -4.1611983396,50.38744458189999,609.6 -4.1613358658,50.38987361900001,609.6 -4.1620251776,50.3922639654,609.6 -4.1632516622,50.3945646657,609.6 -4.1649892459,50.3967266679,609.6 -4.1672009443,50.3987038712,609.6 -4.1698396462,50.4004541095,609.6 -4.1728491155,50.4019400528,609.6 -4.1761651891,50.403130005,609.6 -4.1797171469,50.4039985814,609.6 -4.1834292222,50.404527252,609.6 -4.1872222222,50.40470473780001,609.6 + + + + +
+ + EGR063 DUNGENESS + A circle, 2 NM radius, centred at 505449N 0005717E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Dungeness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight permitted by an aircraft which has taken off from or intends to land at London Ashford (Lydd) Airport flying in accordance with normal aviation practice which remains at least 1.5 NM from the position given at column 1 for Dungeness.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9547222222,50.9469064086,609.6 0.9493030469999999,50.9467298142,609.6 0.9439414384,50.9462019069,609.6 0.9386943478000001,50.9453282944,609.6 0.9336175023,50.944118256,609.6 0.9287648099,50.9425846441,609.6 0.9241877838000001,50.9407437458,609.6 0.9199349934999999,50.9386151102,609.6 0.9160515477,50.93622133869999,609.6 0.9125786149000001,50.9335878442,609.6 0.9095529867,50.9307425803,609.6 0.9070066892999999,50.92771574309999,609.6 0.9049666453,50.9245394495,609.6 0.9034543918999999,50.921247396,609.6 0.9024858558000001,50.9178744997,609.6 0.9020711889,50.9144565275,609.6 0.9022146659,50.91102971669999,609.6 0.9029146436,50.9076303902,609.6 0.9041635837000001,50.904294572,609.6 0.9059481377999999,50.9010576053,609.6 0.9082492934999999,50.89795377900001,609.6 0.9110425797,50.8950159648,609.6 0.9142983296,50.89227527039999,609.6 0.9179819975,50.8897607111,609.6 0.9220545264000001,50.8874989035,609.6 0.9264727623,50.8855137854,609.6 0.9311899111,50.8838263633,609.6 0.9361560329,50.8824544915,609.6 0.9413185687,50.881412684,609.6 0.9466228938999999,50.88071196209999,609.6 0.9520128933000001,50.8803597382,609.6 0.9574315511999999,50.8803597382,609.6 0.9628215505999999,50.88071196209999,609.6 0.9681258757,50.881412684,609.6 0.9732884115000001,50.8824544915,609.6 0.9782545333,50.8838263633,609.6 0.9829716822,50.8855137854,609.6 0.9873899180999999,50.8874989035,609.6 0.9914624469,50.8897607111,609.6 0.9951461149000002,50.89227527039999,609.6 0.9984018648,50.8950159648,609.6 1.001195151,50.89795377900001,609.6 1.0034963066,50.9010576053,609.6 1.0052808608,50.904294572,609.6 1.0065298009,50.9076303902,609.6 1.0072297785,50.91102971669999,609.6 1.0073732555,50.9144565275,609.6 1.0069585887,50.9178744997,609.6 1.0059900525,50.921247396,609.6 1.0044777991,50.9245394495,609.6 1.0024377552,50.92771574309999,609.6 0.9998914577,50.9307425803,609.6 0.9968658296,50.9335878442,609.6 0.9933928967,50.93622133869999,609.6 0.9895094509000001,50.9386151102,609.6 0.9852566606999998,50.9407437458,609.6 0.9806796346,50.9425846441,609.6 0.9758269422,50.944118256,609.6 0.9707500967,50.9453282944,609.6 0.9655030060000001,50.9462019069,609.6 0.9601413974,50.9467298142,609.6 0.9547222222,50.9469064086,609.6 + + + + +
+ + EGR095 SARK + A circle, 3 NM radius, centred at 492546N 0022145W
Upper limit: 2374 FT MSL
Lower limit: SFC
Class: Flight is not permitted except in conformity with any permission granted by or on behalf of the Channel Islands Director of Civil Aviation. The Island of Sark is within Bailiwick of Guernsey territorial waters although within the Brest FIR.

Guernsey SI 1985/21.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3625,49.4794001476,723.5952000000001 -2.3689155084,49.4792247688,723.5952000000001 -2.3752858801,49.4786998665,723.5952000000001 -2.3815662987,49.4778291334,723.5952000000001 -2.3877125865,49.4766186951,723.5952000000001 -2.3936815175,49.4750770665,723.5952000000001 -2.3994311242,49.4732150914,723.5952000000001 -2.4049209946,49.4710458655,723.5952000000001 -2.410112558,49.46858464350001,723.5952000000001 -2.414969357,49.4658487315,723.5952000000001 -2.4194573051,49.4628573634,723.5952000000001 -2.4235449258,49.4596315661,723.5952000000001 -2.4272035732,49.4561940094,723.5952000000001 -2.4304076327,49.45256884679999,723.5952000000001 -2.4331346987,49.4487815446,723.5952000000001 -2.4353657305,49.4448587019,723.5952000000001 -2.4370851827,49.4408278634,723.5952000000001 -2.4382811118,49.43671732549999,723.5952000000001 -2.4389452565,49.4325559366,723.5952000000001 -2.439073092,49.4283728951,723.5952000000001 -2.4386638582,49.42419754379999,723.5952000000001 -2.437720561,49.420059164,723.5952000000001 -2.4362499477,49.41598677069999,723.5952000000001 -2.4342624555,49.41200890900001,723.5952000000001 -2.4317721356,49.4081534549,723.5952000000001 -2.4287965508,49.40444741980001,723.5952000000001 -2.4253566504,49.4009167627,723.5952000000001 -2.4214766204,49.3975862086,723.5952000000001 -2.4171837129,49.3944790766,723.5952000000001 -2.4125080535,49.3916171169,723.5952000000001 -2.4074824296,49.3890203603,723.5952000000001 -2.4021420611,49.3867069782,723.5952000000001 -2.3965243537,49.3846931567,723.5952000000001 -2.3906686384,49.382992984,723.5952000000001 -2.3846158977,49.3816183531,723.5952000000001 -2.3784084803,49.3805788785,723.5952000000001 -2.3720898073,49.3798818303,723.5952000000001 -2.3657040712,49.3795320833,723.5952000000001 -2.3592959288,49.3795320833,723.5952000000001 -2.3529101927,49.3798818303,723.5952000000001 -2.3465915197,49.3805788785,723.5952000000001 -2.3403841023,49.3816183531,723.5952000000001 -2.3343313616,49.382992984,723.5952000000001 -2.3284756463,49.3846931567,723.5952000000001 -2.3228579389,49.3867069782,723.5952000000001 -2.3175175704,49.3890203603,723.5952000000001 -2.3124919465,49.3916171169,723.5952000000001 -2.3078162871,49.3944790766,723.5952000000001 -2.3035233796,49.3975862086,723.5952000000001 -2.2996433496,49.4009167627,723.5952000000001 -2.2962034492,49.40444741980001,723.5952000000001 -2.2932278644,49.4081534549,723.5952000000001 -2.2907375445,49.41200890900001,723.5952000000001 -2.2887500523,49.41598677069999,723.5952000000001 -2.287279439,49.420059164,723.5952000000001 -2.2863361418,49.42419754379999,723.5952000000001 -2.285926908,49.4283728951,723.5952000000001 -2.2860547435,49.4325559366,723.5952000000001 -2.2867188882,49.43671732549999,723.5952000000001 -2.2879148173,49.4408278634,723.5952000000001 -2.2896342695,49.4448587019,723.5952000000001 -2.2918653013,49.4487815446,723.5952000000001 -2.2945923673,49.45256884679999,723.5952000000001 -2.2977964268,49.4561940094,723.5952000000001 -2.3014550742,49.4596315661,723.5952000000001 -2.3055426949,49.4628573634,723.5952000000001 -2.310030643,49.4658487315,723.5952000000001 -2.314887442,49.46858464350001,723.5952000000001 -2.3200790054,49.4710458655,723.5952000000001 -2.3255688758,49.4732150914,723.5952000000001 -2.3313184825,49.4750770665,723.5952000000001 -2.3372874135,49.4766186951,723.5952000000001 -2.3434337013,49.4778291334,723.5952000000001 -2.3497141199,49.4786998665,723.5952000000001 -2.3560844916,49.4792247688,723.5952000000001 -2.3625,49.4794001476,723.5952000000001 + + + + +
+ + EGR101 ALDERMASTON + A circle, 1.5 NM radius, centred at 512203N 0010847W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Aldermaston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1463888889,51.3924695424,731.52 -1.1511093435,51.3922941889,731.52 -1.1557634263,51.391770594,731.52 -1.1602857032,51.3909061194,731.52 -1.164612602,51.38971291910001,731.52 -1.16868331,51.3882077678,731.52 -1.1724406312,51.3864118238,731.52 -1.1758317931,51.3843503304,731.52 -1.1788091878,51.3820522599,731.52 -1.1813310418,51.3795499048,731.52 -1.1833620001,51.376878423,731.52 -1.1848736205,51.374075342,731.52 -1.1858447687,51.3711800313,731.52 -1.1862619106,51.36823314810001,731.52 -1.1861192962,51.36527606590001,731.52 -1.1854190348,51.3623502939,731.52 -1.1841710595,51.3594968935,731.52 -1.1823929815,51.3567559032,731.52 -1.1801098382,51.3541657774,731.52 -1.177353737,51.3517628473,731.52 -1.174163402,51.3495808134,731.52 -1.1705836278,51.3476502732,731.52 -1.1666646506,51.3459982944,731.52 -1.1624614438,51.3446480361,731.52 -1.1580329486,51.34361842609999,731.52 -1.1534412499,51.342923896,731.52 -1.1487507096,51.3425741802,731.52 -1.1440270682,51.3425741802,731.52 -1.1393365279,51.342923896,731.52 -1.1347448292,51.34361842609999,731.52 -1.130316334,51.3446480361,731.52 -1.1261131272,51.3459982944,731.52 -1.12219415,51.3476502732,731.52 -1.1186143758,51.3495808134,731.52 -1.1154240407,51.3517628473,731.52 -1.1126679396,51.3541657774,731.52 -1.1103847963,51.3567559032,731.52 -1.1086067183,51.3594968935,731.52 -1.1073587429,51.3623502939,731.52 -1.1066584816,51.36527606590001,731.52 -1.1065158672,51.36823314810001,731.52 -1.106933009,51.3711800313,731.52 -1.1079041573,51.374075342,731.52 -1.1094157777,51.376878423,731.52 -1.111446736,51.3795499048,731.52 -1.1139685899,51.3820522599,731.52 -1.1169459847,51.3843503304,731.52 -1.1203371465,51.3864118238,731.52 -1.1240944678,51.3882077678,731.52 -1.1281651757,51.38971291910001,731.52 -1.1324920746,51.3909061194,731.52 -1.1370143515,51.391770594,731.52 -1.1416684343,51.3922941889,731.52 -1.1463888889,51.3924695424,731.52 + + + + +
+ + EGR104 BURGHFIELD + A circle, 1 NM radius, centred at 512424N 0010125W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Burghfield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0236111111,51.42331292830001,731.52 -1.0274878214,51.4231354714,731.52 -1.0312818179,51.4226068868,731.52 -1.0349121572,51.4217384523,731.52 -1.0383013983,51.4205486955,731.52 -1.0413772588,51.4190629976,731.52 -1.0440741597,51.4173130507,731.52 -1.0463346245,51.4153361794,731.52 -1.0481105042,51.4131745437,731.52 -1.0493640011,51.4108742375,731.52 -1.0500684699,51.4084843048,731.52 -1.0502089796,51.4060556927,731.52 -1.0497826245,51.403640165,731.52 -1.0487985788,51.40128919829999,731.52 -1.0472778936,51.3990528858,731.52 -1.0452530415,51.3969788707,731.52 -1.0427672195,51.3951113324,731.52 -1.0398734246,51.39349004689999,731.52 -1.0366333234,51.3921495417,731.52 -1.033115938,51.3911183617,731.52 -1.0293961781,51.3904184636,731.52 -1.0255532497,51.3900647491,731.52 -1.0216689725,51.3900647491,731.52 -1.0178260441,51.3904184636,731.52 -1.0141062843,51.3911183617,731.52 -1.0105888988,51.3921495417,731.52 -1.0073487976,51.39349004689999,731.52 -1.0044550028,51.3951113324,731.52 -1.0019691807,51.3969788707,731.52 -0.9999443286,51.3990528858,731.52 -0.9984236434,51.40128919829999,731.52 -0.9974395977,51.403640165,731.52 -0.9970132426,51.4060556927,731.52 -0.9971537523,51.4084843048,731.52 -0.9978582211,51.4108742375,731.52 -0.999111718,51.4131745437,731.52 -1.0008875977,51.4153361794,731.52 -1.0031480625,51.4173130507,731.52 -1.0058449634,51.4190629976,731.52 -1.008920824,51.4205486955,731.52 -1.012310065,51.4217384523,731.52 -1.0159404043,51.4226068868,731.52 -1.0197344008,51.4231354714,731.52 -1.0236111111,51.42331292830001,731.52 + + + + +
+ + EGR105 HIGHGROVE HOUSE + A circle, 1.5 NM radius, centred at 513720N 0021050W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Gloucestershire Constabulary Royalty Household Protection Group;
any aircraft either operated by a member of the Royal Family, or landing in the grounds of Highgrove House at the invitation of the person in charge of the household there, provided that the Gloucestershire Constabulary Royalty Household Protection Group has been informed in advance of such intended flight or landing.

SI 907/2018.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1805555556,51.6471906741,609.6 -2.1853024165,51.6470153274,609.6 -2.1899825335,51.6464917528,609.6 -2.1945301052,51.64562731180001,609.6 -2.1988812033,51.6444341583,609.6 -2.2029746741,51.6429290662,609.6 -2.2067530014,51.6411331935,609.6 -2.2101631173,51.6390717828,609.6 -2.2131571481,51.63677380549999,609.6 -2.2156930867,51.6342715531,609.6 -2.2177353812,51.6316001822,609.6 -2.2192554313,51.6287972192,609.6 -2.2202319857,51.625902032,609.6 -2.2206514358,51.6229552762,609.6 -2.2205080007,51.6199983237,609.6 -2.219803803,51.61707268150001,609.6 -2.2185488324,51.6142194095,609.6 -2.2167607997,51.6114785441,609.6 -2.2144648831,51.6088885376,609.6 -2.2116933704,51.6064857195,609.6 -2.2084852023,51.60430378819999,609.6 -2.204885424,51.6023733396,609.6 -2.2009445523,51.60072143979999,609.6 -2.1967178674,51.5993712465,609.6 -2.1922646389,51.5983416863,609.6 -2.1876472979,51.59764718980001,609.6 -2.1829305648,51.59729749109999,609.6 -2.1781805463,51.59729749109999,609.6 -2.1734638132,51.59764718980001,609.6 -2.1688464722,51.5983416863,609.6 -2.1643932438,51.5993712465,609.6 -2.1601665588,51.60072143979999,609.6 -2.1562256871,51.6023733396,609.6 -2.1526259088,51.60430378819999,609.6 -2.1494177407,51.6064857195,609.6 -2.146646228,51.6088885376,609.6 -2.1443503114,51.6114785441,609.6 -2.1425622788,51.6142194095,609.6 -2.1413073081,51.61707268150001,609.6 -2.1406031104,51.6199983237,609.6 -2.1404596754,51.6229552762,609.6 -2.1408791254,51.625902032,609.6 -2.1418556798,51.6287972192,609.6 -2.1433757299,51.6316001822,609.6 -2.1454180245,51.6342715531,609.6 -2.147953963,51.63677380549999,609.6 -2.1509479938,51.6390717828,609.6 -2.1543581097,51.6411331935,609.6 -2.1581364371,51.6429290662,609.6 -2.1622299078,51.6444341583,609.6 -2.1665810059,51.64562731180001,609.6 -2.1711285777,51.6464917528,609.6 -2.1758086946,51.6470153274,609.6 -2.1805555556,51.6471906741,609.6 + + + + +
+ + EGR106 RAYMILL HOUSE, LACOCK + A circle, 1 NM radius, centred at 512523N 0020646W
Upper limit: 1600 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Services;
any aircraft flying in the service of Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight.

Flying in accordance with an agreed exemption issued by, or with the permission of, the Wiltshire Police Constabulary Royalty Protection Department.

SI 703/2021.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1127777778,51.4397017704,487.68 -2.1166558753,51.4395243139,487.68 -2.1204512294,51.4389957307,487.68 -2.1240828677,51.4381272985,487.68 -2.1274733213,51.4369375448,487.68 -2.1305502821,51.43545185089999,487.68 -2.1332481474,51.4337019086,487.68 -2.1355094204,51.4317250426,487.68 -2.1372859347,51.42956341279999,487.68 -2.1385398793,51.42726311289999,487.68 -2.1392445993,51.42487318680001,487.68 -2.1393851584,51.4224445816,487.68 -2.13895865,51.4200290607,487.68 -2.1379742516,51.4176781007,487.68 -2.136453022,51.4154417947,487.68 -2.1344274453,51.4133677857,487.68 -2.1319407342,51.4115002529,487.68 -2.1290459045,51.4098789722,487.68 -2.1258046448,51.408538471,487.68 -2.122286002,51.40750729410001,487.68 -2.1185649125,51.4068073981,487.68 -2.1147206105,51.4064536847,487.68 -2.110834945,51.4064536847,487.68 -2.106990643,51.4068073981,487.68 -2.1032695536,51.40750729410001,487.68 -2.0997509107,51.408538471,487.68 -2.096509651,51.4098789722,487.68 -2.0936148214,51.4115002529,487.68 -2.0911281102,51.4133677857,487.68 -2.0891025336,51.4154417947,487.68 -2.0875813039,51.4176781007,487.68 -2.0865969056,51.4200290607,487.68 -2.0861703972,51.4224445816,487.68 -2.0863109563,51.42487318680001,487.68 -2.0870156763,51.42726311289999,487.68 -2.0882696209,51.42956341279999,487.68 -2.0900461352,51.4317250426,487.68 -2.0923074081,51.4337019086,487.68 -2.0950052735,51.43545185089999,487.68 -2.0980822343,51.4369375448,487.68 -2.1014726879,51.4381272985,487.68 -2.1051043261,51.4389957307,487.68 -2.1088996802,51.4395243139,487.68 -2.1127777778,51.4397017704,487.68 + + + + +
+ + EGR153 HINKLEY POINT + A circle, 2 NM radius, centred at 511233N 0030749W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hinkley Point, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight permitted by a helicopter flying within the Bridgewater Bay Danger Area with the permission of the person in charge of that Area and in accordance with any conditions to which that permission is subject which remains at least 1 NM from the position given at column 1 for Hinkley Point.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1301805556,51.2423352721,609.6 -3.1356343719,51.2421586853,609.6 -3.141030252399999,51.24163080089999,609.6 -3.1463108803,51.24075722639999,609.6 -3.1514201712,51.239547241,609.6 -3.1563038717,51.23801369660001,609.6 -3.1609101384,51.2361728802,609.6 -3.1651900912,51.23404434020001,609.6 -3.1690983329,51.2316506773,609.6 -3.1725934322,51.229017304,609.6 -3.1756383627,51.2261721727,609.6 -3.178200894600001,51.22314547860001,609.6 -3.1802539342,51.21996933749999,609.6 -3.1817758082,51.21667744429999,609.6 -3.1827504897,51.2133047149,609.6 -3.183167763400001,51.2098869144,609.6 -3.183023329200001,51.2064602785,609.6 -3.1823188426,51.2030611281,609.6 -3.181061891500001,51.1997254852,609.6 -3.179265911199999,51.1964886911,609.6 -3.1769500369,51.1933850325,609.6 -3.174138896900001,51.190447379,609.6 -3.1708623484,51.1877068364,609.6 -3.167155158,51.1851924178,609.6 -3.1630566323,51.182930738,609.6 -3.1586102005,51.180945733,609.6 -3.153862955,51.1792584078,609.6 -3.1488651536,51.17788661520001,609.6 -3.1436696898,51.17684486809999,609.6 -3.1383315354,51.17614418700001,609.6 -3.1329071624,51.17579198369999,609.6 -3.1274539487,51.17579198369999,609.6 -3.1220295757,51.17614418700001,609.6 -3.116691421300001,51.17684486809999,609.6 -3.1114959575,51.17788661520001,609.6 -3.1064981561,51.1792584078,609.6 -3.1017509106,51.180945733,609.6 -3.0973044788,51.182930738,609.6 -3.0932059531,51.1851924178,609.6 -3.0894987627,51.1877068364,609.6 -3.0862222142,51.190447379,609.6 -3.0834110742,51.1933850325,609.6 -3.0810951999,51.1964886911,609.6 -3.0792992196,51.1997254852,609.6 -3.0780422685,51.2030611281,609.6 -3.0773377819,51.2064602785,609.6 -3.0771933477,51.2098869144,609.6 -3.0776106214,51.2133047149,609.6 -3.0785853029,51.21667744429999,609.6 -3.0801071769,51.21996933749999,609.6 -3.0821602165,51.22314547860001,609.6 -3.084722748399999,51.2261721727,609.6 -3.0877676789,51.229017304,609.6 -3.0912627782,51.2316506773,609.6 -3.0951710199,51.23404434020001,609.6 -3.0994509727,51.2361728802,609.6 -3.1040572394,51.23801369660001,609.6 -3.1089409399,51.239547241,609.6 -3.1140502308,51.24075722639999,609.6 -3.1193308587,51.24163080089999,609.6 -3.124726739200001,51.2421586853,609.6 -3.1301805556,51.2423352721,609.6 + + + + +
+ + EGR154 OLDBURY + A circle, 2 NM radius, centred at 513852N 0023415W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Oldbury, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5708638889,51.6811522104,609.6 -2.5763702602,51.68097563490001,609.6 -2.5818181352,51.6804477843,609.6 -2.5871496433,51.6795742659,609.6 -2.5923081578,51.67836435870001,609.6 -2.597238901,51.67683091410001,609.6 -2.6018895292,51.6749902186,609.6 -2.6062106904,51.6728618197,609.6 -2.6101565501,51.6704683175,609.6 -2.613685278,51.66783512319999,609.6 -2.6167594919,51.664990188,609.6 -2.6193466528,51.66196370550001,609.6 -2.6214194077,51.6587877899,609.6 -2.6229558766,51.6554961341,609.6 -2.6239398805,51.6521236517,609.6 -2.6243611085,51.6487061056,609.6 -2.6242152215,51.6452797286,609.6 -2.6235038936,51.6418808392,609.6 -2.6222347885,51.6385454562,609.6 -2.6204214729,51.63530891790001,609.6 -2.6180832685,51.6322055079,609.6 -2.6152450422,51.62926809290001,609.6 -2.6119369398,51.6265277754,609.6 -2.6081940633,51.6240135655,609.6 -2.6040560978,51.62175207540001,609.6 -2.5995668902,51.6197672383,609.6 -2.5947739853,51.6180800568,609.6 -2.5897281231,51.61670838180001,609.6 -2.5844827046,51.6156667245,609.6 -2.5790932284,51.6149661039,609.6 -2.5736167077,51.6146139311,609.6 -2.5681110701,51.6146139311,609.6 -2.5626345494,51.6149661039,609.6 -2.5572450732,51.6156667245,609.6 -2.5519996547,51.61670838180001,609.6 -2.5469537925,51.6180800568,609.6 -2.5421608876,51.6197672383,609.6 -2.53767168,51.62175207540001,609.6 -2.5335337145,51.6240135655,609.6 -2.529790838,51.6265277754,609.6 -2.5264827356,51.62926809290001,609.6 -2.5236445093,51.6322055079,609.6 -2.5213063049,51.63530891790001,609.6 -2.5194929893,51.6385454562,609.6 -2.5182238841,51.6418808392,609.6 -2.5175125563,51.6452797286,609.6 -2.5173666693,51.6487061056,609.6 -2.5177878972,51.6521236517,609.6 -2.5187719012,51.6554961341,609.6 -2.5203083701,51.6587877899,609.6 -2.522381125,51.66196370550001,609.6 -2.5249682859,51.664990188,609.6 -2.5280424998,51.66783512319999,609.6 -2.5315712277,51.6704683175,609.6 -2.5355170874,51.6728618197,609.6 -2.5398382486,51.6749902186,609.6 -2.5444888768,51.67683091410001,609.6 -2.54941962,51.67836435870001,609.6 -2.5545781345,51.6795742659,609.6 -2.5599096425,51.6804477843,609.6 -2.5653575176,51.68097563490001,609.6 -2.5708638889,51.6811522104,609.6 + + + + +
+ + EGR155 BERKELEY + A circle, 2 NM radius, centred at 514134N 0022936W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Berkeley, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4933,51.7260130658,609.6 -2.4988118196,51.7258364915,609.6 -2.504265085,51.7253086443,609.6 -2.5096018678,51.72443513160001,609.6 -2.5147654852,51.7232252324,609.6 -2.5197011053,51.7216917979,609.6 -2.5243563324,51.7198511147,609.6 -2.5286817657,51.7177227303,609.6 -2.5326315251,51.7153292444,609.6 -2.5361637393,51.7126960683,609.6 -2.539240989,51.7098511531,609.6 -2.5418307031,51.70682469219999,609.6 -2.5439055018,51.7036487996,609.6 -2.5454434837,51.700357168,609.6 -2.5464284541,51.6969847108,609.6 -2.5468500919,51.6935671906,609.6 -2.5467040542,51.69014084009999,609.6 -2.5459920171,51.68674197730001,609.6 -2.5447216519,51.6834066208,609.6 -2.5429065392,51.6801701086,609.6 -2.5405660198,51.6770667241,609.6 -2.5377249855,51.67412933340001,609.6 -2.5344136119,51.6713890388,609.6 -2.5306670359,51.6688748503,609.6 -2.5265249817,51.6666133795,609.6 -2.5220313396,51.6646285596,609.6 -2.5172337012,51.6629413928,609.6 -2.5121828567,51.6615697298,609.6 -2.5069322595,51.66052808170001,609.6 -2.5015374629,51.6598274673,609.6 -2.4960555361,51.6594752976,609.6 -2.4905444639,51.6594752976,609.6 -2.4850625371,51.6598274673,609.6 -2.4796677405,51.66052808170001,609.6 -2.4744171433,51.6615697298,609.6 -2.4693662988,51.6629413928,609.6 -2.4645686604,51.6646285596,609.6 -2.4600750183,51.6666133795,609.6 -2.4559329641,51.6688748503,609.6 -2.4521863881,51.6713890388,609.6 -2.4488750145,51.67412933340001,609.6 -2.4460339802,51.6770667241,609.6 -2.4436934608,51.6801701086,609.6 -2.4418783481,51.6834066208,609.6 -2.4406079829,51.68674197730001,609.6 -2.4398959458,51.69014084009999,609.6 -2.4397499081,51.6935671906,609.6 -2.4401715459,51.6969847108,609.6 -2.4411565163,51.700357168,609.6 -2.4426944982,51.7036487996,609.6 -2.4447692969,51.70682469219999,609.6 -2.447359011,51.7098511531,609.6 -2.4504362607,51.7126960683,609.6 -2.4539684749,51.7153292444,609.6 -2.4579182343,51.7177227303,609.6 -2.4622436676,51.7198511147,609.6 -2.4668988947,51.7216917979,609.6 -2.4718345148,51.7232252324,609.6 -2.4769981322,51.72443513160001,609.6 -2.482334915,51.7253086443,609.6 -2.4877881804,51.7258364915,609.6 -2.4933,51.7260130658,609.6 + + + + +
+ + EGR156 WINDSOR CASTLE + A circle, 1.25 NM radius, centred at 512902N 0003614W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft operating for or on behalf of National Police Air Service;
any aircraft operating for or on behalf of The Helicopter Emergency Medical Service;
any aircraft operating for or on behalf of The Maritime and Coastguard Agency for the purposes of search and rescue operations;
any aircraft operating for or on behalf of The King's Helicopter Flight;
any aircraft operated by a member of the Royal Family;
any aircraft flying in accordance with an agreed exemption issued by, or with the permission of, the Metropolitan Police (Royalty and Special Protection);
or landing in the grounds of Windsor Great Park at the invitation of the Director of Royal Travel provided that Protective Security Operations (PSO) has been informed in advance of such intended flight or landing;
any aircraft approaching to, or departing from, London Heathrow Airport.

SI 1137/2021.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6038888889,51.5046964329,762 -0.6082407864,51.50451834100001,762 -0.6125181213999999,51.5039871169,762 -0.6166476141,51.5031118618,762 -0.6205585275,51.5019075706,762 -0.6241838830999999,51.5003948741,762 -0.6274616116,51.4985996837,762 -0.630335617,51.4965527468,762 -0.6327567375000001,51.4942891181,762 -0.634683586,51.4918475578,762 -0.6360832551,51.4892698664,762 -0.6369318764,51.48660016809999,762 -0.6372150232,51.4838841541,762 -0.6369279509,51.4811683001,762 -0.6360756717,51.4784990711,762 -0.6346728614,51.4759221263,762 -0.6327436027,51.4734815389,762 -0.630320967,51.47121904320001,762 -0.6274464448,51.46917332219999,762 -0.6241692331000001,51.4673793477,762 -0.6205453926,51.4658677841,762 -0.6166368896,51.4646644659,762 -0.612510538,51.4637899573,762 -0.6082368609,51.46325920240001,762 -0.6038888889,51.4630812707,762 -0.5995409168,51.46325920240001,762 -0.5952672398,51.4637899573,762 -0.5911408882,51.4646644659,762 -0.5872323852,51.4658677841,762 -0.5836085447,51.4673793477,762 -0.5803313329999999,51.46917332219999,762 -0.5774568108,51.47121904320001,762 -0.5750341751,51.4734815389,762 -0.5731049163,51.4759221263,762 -0.5717021061000001,51.4784990711,762 -0.5708498268,51.4811683001,762 -0.5705627546000001,51.4838841541,762 -0.5708459014,51.48660016809999,762 -0.5716945227,51.4892698664,762 -0.5730941918,51.4918475578,762 -0.5750210402,51.4942891181,762 -0.5774421608,51.4965527468,762 -0.5803161661,51.4985996837,762 -0.5835938946,51.5003948741,762 -0.5872192503,51.5019075706,762 -0.5911301637,51.5031118618,762 -0.5952596563,51.5039871169,762 -0.5995369914000001,51.50451834100001,762 -0.6038888889,51.5046964329,762 + + + + +
+ + EGR157 HYDE PARK + 513212N 0000911W -
513020N 0000648W thence clockwise by the arc of a circle radius 0.55 NM centred on 513000N 0000730W to
513001N 0000637W -
512917N 0000634W thence clockwise by the arc of a circle radius 0.55 NM centred on 512915N 0000726W to
512852N 0000649W -
512834N 0000719W thence clockwise by the arc of a circle radius 0.55 NM centred on 512857N 0000756W to
512858N 0000849W -
512921N 0000847W -
512939N 0001132W thence clockwise by the arc of a circle radius 0.55 NM centred on 513011N 0001123W to
513028N 0001209W -
513208N 0001038W thence clockwise by the arc of a circle radius 0.55 NM centred on 513151N 0000952W to -
513212N 0000911W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 1300/2017

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1529333333,51.53661111109999,426.7200000000001 -0.1549267573,51.53789408709999,426.7200000000001 -0.1572818369,51.5389111961,426.7200000000001 -0.1599088899,51.5396236997,426.7200000000001 -0.1627078613,51.5400044583,426.7200000000001 -0.1655721364,51.5400389683,426.7200000000001 -0.1683926087,51.5397259152,426.7200000000001 -0.1710618431,51.5390772237,426.7200000000001 -0.1734781752,51.53811760280001,426.7200000000001 -0.1755495885,51.5368836029,426.7200000000001 -0.1771972222,51.5354222222,426.7200000000001 -0.2023722222,51.5076638889,426.7200000000001 -0.2035115549,51.5060699613,426.7200000000001 -0.2041447262,51.5043699176,426.7200000000001 -0.2042494731,51.5026257804,426.7200000000001 -0.2038220493,51.5009009245,426.7200000000001 -0.2028780428,51.4992580171,426.7200000000001 -0.2014518003,51.4977567415,426.7200000000001 -0.1995951734,51.4964516304,426.7200000000001 -0.1973756297,51.4953900866,426.7200000000001 -0.1948738011,51.4946106635,426.7200000000001 -0.1921805556,51.4941416667,426.7200000000001 -0.1464694444,51.4890388889,426.7200000000001 -0.1468722222,51.48287500000001,426.7200000000001 -0.1467340709,51.4811955082,426.7200000000001 -0.1461068208,51.4795600798,426.7200000000001 -0.1450111174,51.4780238809,426.7200000000001 -0.1434839716,51.4766387391,426.7200000000001 -0.141576937,51.4754513811,426.7200000000001 -0.1393543671,51.47450185809999,426.7200000000001 -0.1368912443,51.47382219699999,426.7200000000001 -0.1342706517,51.4734353207,426.7200000000001 -0.1315809745,51.4733542773,426.7200000000001 -0.1289129236,51.4735818,426.7200000000001 -0.1263564821,51.4741102153,426.7200000000001 -0.1239978753,51.4749217016,426.7200000000001 -0.1219166667,51.4759888889,426.7200000000001 -0.1136111111,51.48111111110001,426.7200000000001 -0.1120090522,51.482252708,426.7200000000001 -0.1107683543,51.483560414,426.7200000000001 -0.109891236,51.4849782611,426.7200000000001 -0.1094019057,51.4864671731,426.7200000000001 -0.1093138889,51.4879861111,426.7200000000001 -0.1102416667,51.5003194444,426.7200000000001 -0.1105268172,51.5017362939,426.7200000000001 -0.1111609871,51.50310830229999,426.7200000000001 -0.1121293381,51.50440206899999,426.7200000000001 -0.1134083333,51.5055861111,426.7200000000001 -0.1529333333,51.53661111109999,426.7200000000001 + + + + +
+ + EGR158 CITY OF LONDON + 513125N 0000547W -
513118N 0000439W -
513043N 0000418W -
513016N 0000433W -
513037N 0000704W -
513108N 0000653W -
513125N 0000547W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 2092/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.09652500000000001,51.52371388890001,426.7200000000001 -0.1147444444,51.5188833333,426.7200000000001 -0.1176944444,51.5102972222,426.7200000000001 -0.0757138889,51.5044888889,426.7200000000001 -0.0716472222,51.51206666669999,426.7200000000001 -0.07758611109999999,51.5216055556,426.7200000000001 -0.09652500000000001,51.52371388890001,426.7200000000001 + + + + +
+ + EGR159 ISLE OF DOGS + 513035N 0000025W -
512954N 0000033W -
512938N 0000022W thence clockwise by the arc of a circle radius 0.3 NM centred on 512931N 0000049W to
512921N 0000113W -
513000N 0000154W thence clockwise by the arc of a circle radius 0.55 NM centred on 513018N 0000110W to -
513035N 0000025W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit;
any aircraft approaching to, or departing from, London/City Airport.

See also ENR 1.1, paragraph 4.1.6.

SI 2091/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0068583333,51.5097055556,426.7200000000001 -0.0082867913,51.5111814939,426.7200000000001 -0.0103077723,51.5123684169,426.7200000000001 -0.0126486151,51.51329883229999,426.7200000000001 -0.0152268831,51.5139399674,426.7200000000001 -0.0179517632,51.51426923799999,426.7200000000001 -0.020727269,51.51427504499999,426.7200000000001 -0.0234556276,51.5139571838,426.7200000000001 -0.0260407298,51.5133268516,426.7200000000001 -0.0283915214,51.51240625220001,426.7200000000001 -0.030425215,51.5112278124,426.7200000000001 -0.0320702078,51.5098330386,426.7200000000001 -0.0332686036,51.50827105250001,426.7200000000001 -0.0339782479,51.5065968595,426.7200000000001 -0.0341742076,51.5048694103,426.7200000000001 -0.0338496416,51.5031495242,426.7200000000001 -0.033016033,51.5014977474,426.7200000000001 -0.0317027778,51.4999722222,426.7200000000001 -0.0202666667,51.48911111110001,426.7200000000001 -0.0187899397,51.4881604117,426.7200000000001 -0.0170196811,51.4874451822,426.7200000000001 -0.0150110296,51.4870446916,426.7200000000001 -0.0129044713,51.4869869497,426.7200000000001 -0.0108473335,51.4872759947,426.7200000000001 -0.008983490199999999,51.4878916114,426.7200000000001 -0.0074433086,51.4887907435,426.7200000000001 -0.0063345359,51.4899105027,426.7200000000001 -0.005734762,51.4911725642,426.7200000000001 -0.005685986,51.49248864270001,426.7200000000001 -0.0061916667,51.4937666667,426.7200000000001 -0.009272222199999999,51.49840277780001,426.7200000000001 -0.0068583333,51.5097055556,426.7200000000001 + + + + +
+ + EGR217 SIZEWELL + A circle, 2 NM radius, centred at 521250N 0013707E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sizewell, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.6186111111,52.2471767692,609.6 1.6130349418,52.2470002081,609.6 1.6075180128,52.24647240069999,609.6 1.602118931,52.2455989541,609.6 1.596895043,52.2443891468,609.6 1.5919018227,52.2428558299,609.6 1.5871922788,52.241015289,609.6 1.5828163894,52.2388870708,609.6 1.5788205702,52.2364937743,609.6 1.5752471812,52.23386080929999,609.6 1.5721340772,52.2310161253,609.6 1.5695142078,52.2279899142,609.6 1.5674152705,52.2248142877,609.6 1.5658594196,52.22152293649999,609.6 1.5648630359,52.2181507711,609.6 1.5644365577,52.2147335516,609.6 1.5645843754,52.2113075073,609.6 1.5653047901,52.2079089532,609.6 1.5665900379,52.2045739043,609.6 1.5684263769,52.201337695,609.6 1.5707942383,52.198234605,609.6 1.5736684378,52.19529749679999,609.6 1.5770184465,52.19255746899999,609.6 1.5808087168,52.190043528,609.6 1.5849990611,52.1877822821,609.6 1.5895450777,52.1857976613,609.6 1.5943986212,52.184110665,609.6 1.5995083107,52.1827391416,609.6 1.6048200718,52.1816975999,609.6 1.6102777059,52.1809970574,609.6 1.6158234815,52.1806449239,609.6 1.6213987407,52.1806449239,609.6 1.6269445163,52.1809970574,609.6 1.6324021504,52.1816975999,609.6 1.6377139115,52.1827391416,609.6 1.642823601,52.184110665,609.6 1.6476771445,52.1857976613,609.6 1.6522231611,52.1877822821,609.6 1.6564135054,52.190043528,609.6 1.6602037757,52.19255746899999,609.6 1.6635537844,52.19529749679999,609.6 1.6664279839,52.198234605,609.6 1.6687958453,52.201337695,609.6 1.6706321843,52.2045739043,609.6 1.6719174321,52.2079089532,609.6 1.6726378469,52.2113075073,609.6 1.6727856645,52.2147335516,609.6 1.6723591863,52.2181507711,609.6 1.6713628027,52.22152293649999,609.6 1.6698069517,52.2248142877,609.6 1.6677080144,52.2279899142,609.6 1.6650881451,52.2310161253,609.6 1.661975041,52.23386080929999,609.6 1.658401652,52.2364937743,609.6 1.6544058329,52.2388870708,609.6 1.6500299435,52.241015289,609.6 1.6453203995,52.2428558299,609.6 1.6403271792,52.2443891468,609.6 1.6351032913,52.2455989541,609.6 1.6297042095,52.24647240069999,609.6 1.6241872805,52.2470002081,609.6 1.6186111111,52.2471767692,609.6 + + + + +
+ + EGR219 SANDRINGHAM HOUSE + 524819N 0003104E thence clockwise by the arc of a circle radius 1.5 NM centred on 524948N 0003049E to
525117N 0003033E -
525132N 0003424E thence anti-clockwise by the arc of a circle radius 1.5 NM centred on 525003N 0003447E to
524834N 0003510E -
524819N 0003104E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;
any aircraft landing in the grounds of Sandringham House at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended landing.

SI 1734/2015.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5177777778,52.80527777780001,609.6 0.5861111111,52.8094444444,609.6 0.5813312013,52.8091625577,609.6 0.5765296282,52.8092184194,609.6 0.5717711605,52.80961150990001,609.6 0.5671200484,52.8103365217,609.6 0.5626390999000001,52.8113836653,609.6 0.5583888366,52.81273880060001,609.6 0.5544266794,52.8143836274,609.6 0.5508061755,52.8162959307,609.6 0.5475762763000001,52.8184498803,609.6 0.5447806761,52.82081637770001,609.6 0.5424572208,52.8233634481,609.6 0.5406373936,52.82605667120001,609.6 0.5393458868,52.8288596452,609.6 0.5386002629,52.8317344777,609.6 0.5384107123,52.8346422975,609.6 0.5387799094,52.8375437796,609.6 0.5397029712,52.8403996768,609.6 0.5411675166,52.8431713511,609.6 0.5431538286000001,52.8458212968,609.6 0.5456351161,52.8483136486,609.6 0.5485778725,52.8506146684,609.6 0.5519423253,52.8526932029,609.6 0.5556829735,52.85452110690001,609.6 0.559749202,52.8560736255,609.6 0.5640859678,52.85732973109999,609.6 0.5686345472,52.8582724089,609.6 0.5733333333,52.8588888889,609.6 0.5091666667,52.8547222222,609.6 0.5044716918,52.8542266656,609.6 0.4998968511,52.85342217749999,609.6 0.4955069903,52.8523021167,609.6 0.4913613018999999,52.8508815899,609.6 0.4875156698,52.8491797549,609.6 0.4840219144,52.8472195607,609.6 0.4809270925,52.8450274369,609.6 0.4782728636,52.8426329362,609.6 0.4760949294,52.8400683345,609.6 0.4744225554,52.8373681946,609.6 0.4732781803,52.8345688996,609.6 0.4726771183999999,52.8317081614,609.6 0.4726273583,52.8288245125,609.6 0.4731294608,52.825956786,609.6 0.4741765578,52.8231435933,609.6 0.4757544502,52.8204228042,609.6 0.4778418043000001,52.81783103770001,609.6 0.4804104435,52.81540317,609.6 0.483425732,52.8131718661,609.6 0.4868470429,52.81116714169999,609.6 0.4906283068,52.80941596089999,609.6 0.4947186319,52.8079418741,609.6 0.4990629881,52.8067647034,609.6 0.5036029447,52.8059002767,609.6 0.5082774536,52.8053602162,609.6 0.513023667,52.8051517825,609.6 0.5177777778,52.80527777780001,609.6 + + + + +
+ + EGR220 ANMER HALL + A circle, 1.5 NM radius, centred at 525003N 0003447E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;
any aircraft either operated by a member of the Royal Family, or landing in the grounds of Anmer Hall at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended flight or landing.

SI 1735/2015.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5797222222,52.859129963,609.6 0.5748442042,52.8589546483,609.6 0.5700347793,52.8584311691,609.6 0.5653615715,52.85756688639999,609.6 0.5608902795,52.8563739525,609.6 0.5566837497,52.8548691396,609.6 0.5528010891,52.8530736028,609.6 0.5492968325000001,52.85101258160001,609.6 0.5462201754,52.8487150433,609.6 0.5436142829,52.84621327499999,609.6 0.5415156856,52.8435424277,609.6 0.539953769,52.8407400216,609.6 0.5389503657,52.8378454177,609.6 0.5385194541,52.8348992641,609.6 0.5386669678,52.8319429244,609.6 0.5393907192,52.829017897,609.6 0.5406804363,52.82616523259999,609.6 0.5425179136,52.8234249585,609.6 0.5448772732,52.8208355175,609.6 0.5477253323,52.8184332298,609.6 0.5510220733,52.81625178510001,609.6 0.5547212068,52.81432177100001,609.6 0.5587708226,52.8126702457,609.6 0.5631141169,52.8113203607,609.6 0.5676901877,52.81029103670001,609.6 0.5724348857,52.8095967002,609.6 0.5772817097,52.8092470821,609.6 0.5821627347,52.8092470821,609.6 0.5870095588000001,52.8095967002,609.6 0.5917542567,52.81029103670001,609.6 0.5963303275,52.8113203607,609.6 0.6006736219,52.8126702457,609.6 0.6047232376,52.81432177100001,609.6 0.6084223711,52.81625178510001,609.6 0.6117191121,52.8184332298,609.6 0.6145671713,52.8208355175,609.6 0.6169265308,52.8234249585,609.6 0.6187640082,52.82616523259999,609.6 0.6200537253,52.829017897,609.6 0.6207774766,52.8319429244,609.6 0.6209249903,52.8348992641,609.6 0.6204940787,52.8378454177,609.6 0.6194906755,52.8407400216,609.6 0.6179287589,52.8435424277,609.6 0.6158301615,52.84621327499999,609.6 0.613224269,52.8487150433,609.6 0.6101476119,52.85101258160001,609.6 0.6066433553,52.8530736028,609.6 0.6027606947,52.8548691396,609.6 0.5985541649,52.8563739525,609.6 0.594082873,52.85756688639999,609.6 0.5894096651,52.8584311691,609.6 0.5846002403,52.8589546483,609.6 0.5797222222,52.859129963,609.6 + + + + +
+ + EGR311 CAPENHURST + A circle, 2 NM radius, centred at 531550N 0025708W
Upper limit: 2200 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9522222222,53.2971708423,670.5600000000001 -2.9579341894,53.2969943076,670.5600000000001 -2.9635854683,53.2964665791,670.5600000000001 -2.9691160199,53.2955932635,670.5600000000001 -2.9744670965,53.29438363889999,670.5600000000001 -2.9795818698,53.2928505553,670.5600000000001 -2.9844060374,53.2910102972,670.5600000000001 -2.9888884027,53.2888824097,670.5600000000001 -2.9929814192,53.2864894898,670.5600000000001 -2.9966416966,53.2838569448,670.5600000000001 -2.9998304605,53.2810127215,670.5600000000001 -3.0025139625,53.2779870081,670.5600000000001 -3.0046638354,53.2748119126,670.5600000000001 -3.0062573909,53.2715211209,670.5600000000001 -3.0072778557,53.2681495386,670.5600000000001 -3.007714544200001,53.26473292,670.5600000000001 -3.0075629662,53.2613074885,670.5600000000001 -3.0068248687,53.25790955219999,670.5600000000001 -3.0055082113,53.2545751195,670.5600000000001 -3.0036270764,53.2513395174,670.5600000000001 -3.0012015142,53.248237018,670.5600000000001 -2.9982573261,53.2453004767,670.5600000000001 -2.9948257867,53.2425609844,670.5600000000001 -2.9909433102,53.2400475405,670.5600000000001 -2.9866510624,53.23778674650001,670.5600000000001 -2.981994524000001,53.2358025259,670.5600000000001 -2.9770230091,53.2341158725,670.5600000000001 -2.9717891449,53.2327446297,670.5600000000001 -2.9663483163,53.2317033022,670.5600000000001 -2.9607580832,53.2310029042,670.5600000000001 -2.955077575,53.2306508436,670.5600000000001 -2.9493668694,53.2306508436,670.5600000000001 -2.9436863612,53.2310029042,670.5600000000001 -2.9380961281,53.2317033022,670.5600000000001 -2.9326552995,53.2327446297,670.5600000000001 -2.927421435299999,53.2341158725,670.5600000000001 -2.9224499205,53.2358025259,670.5600000000001 -2.917793382,53.23778674650001,670.5600000000001 -2.9135011342,53.2400475405,670.5600000000001 -2.9096186577,53.2425609844,670.5600000000001 -2.9061871184,53.2453004767,670.5600000000001 -2.903242930199999,53.248237018,670.5600000000001 -2.9008173681,53.2513395174,670.5600000000001 -2.8989362332,53.2545751195,670.5600000000001 -2.897619575799999,53.25790955219999,670.5600000000001 -2.8968814782,53.2613074885,670.5600000000001 -2.8967299002,53.26473292,670.5600000000001 -2.8971665887,53.2681495386,670.5600000000001 -2.8981870536,53.2715211209,670.5600000000001 -2.8997806091,53.2748119126,670.5600000000001 -2.901930482,53.2779870081,670.5600000000001 -2.9046139839,53.2810127215,670.5600000000001 -2.9078027478,53.2838569448,670.5600000000001 -2.911463025200001,53.2864894898,670.5600000000001 -2.915556041699999,53.2888824097,670.5600000000001 -2.920038406999999,53.2910102972,670.5600000000001 -2.924862574700001,53.2928505553,670.5600000000001 -2.9299773479,53.29438363889999,670.5600000000001 -2.9353284246,53.2955932635,670.5600000000001 -2.9408589761,53.2964665791,670.5600000000001 -2.946510255,53.2969943076,670.5600000000001 -2.9522222222,53.2971708423,670.5600000000001 + + + + +
+ + EGR312 SPRINGFIELDS + A circle, 2 NM radius, centred at 534634N 0024815W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted at not less than 1670 FT above mean sea level for the purpose of landing at Blackpool Airport.

Flight permitted in airspace lying south of a straight line drawn from 534644N 0024454W to 534513N 0025044W for the purpose of landing at or taking off from Warton Aerodrome.

Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Springfields, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8041666667,53.8093901962,640.08 -2.8099480329,53.8092136741,640.08 -2.8156679709,53.8086859834,640.08 -2.8212657095,53.8078127308,640.08 -2.8266817852,53.8066031939,640.08 -2.8318586771,53.8050702223,640.08 -2.836741422,53.8032301001,640.08 -2.8412782002,53.8011023716,640.08 -2.8454208877,53.7987096328,640.08 -2.8491255674,53.7960772901,640.08 -2.852352995,53.7932332887,640.08 -2.855069014,53.7902078153,640.08 -2.857244915,53.787032976,640.08 -2.8588577369,53.78374245450001,640.08 -2.859890506,53.780371154,640.08 -2.8603324101,53.7769548261,640.08 -2.8601789083,53.7735296912,640.08 -2.8594317722,53.77013205429999,640.08 -2.8580990616,53.7667979202,640.08 -2.8561950329,53.7635626126,640.08 -2.8537399825,53.7604604,640.08 -2.850760027000001,53.7575241339,640.08 -2.8472868223,53.7547849019,640.08 -2.8433572254,53.7522716996,640.08 -2.839012901999999,53.7500111253,640.08 -2.8342998842,53.7480270994,640.08 -2.829268083400001,53.7463406129,640.08 -2.8239707635,53.7449695067,640.08 -2.8184639791,53.7439282835,640.08 -2.8128059857,53.7432279559,640.08 -2.807056627,53.7428759307,640.08 -2.8012767063,53.7428759307,640.08 -2.7955273476,53.7432279559,640.08 -2.7898693542,53.7439282835,640.08 -2.7843625699,53.7449695067,640.08 -2.7790652499,53.7463406129,640.08 -2.7740334492,53.7480270994,640.08 -2.7693204313,53.7500111253,640.08 -2.7649761079,53.7522716996,640.08 -2.7610465111,53.7547849019,640.08 -2.7575733064,53.7575241339,640.08 -2.7545933508,53.7604604,640.08 -2.7521383004,53.7635626126,640.08 -2.7502342717,53.7667979202,640.08 -2.7489015611,53.77013205429999,640.08 -2.748154425,53.7735296912,640.08 -2.7480009232,53.7769548261,640.08 -2.7484428274,53.780371154,640.08 -2.7494755964,53.78374245450001,640.08 -2.7510884183,53.787032976,640.08 -2.7532643193,53.7902078153,640.08 -2.7559803383,53.7932332887,640.08 -2.759207766,53.7960772901,640.08 -2.7629124456,53.7987096328,640.08 -2.7670551331,53.8011023716,640.08 -2.7715919114,53.8032301001,640.08 -2.7764746563,53.8050702223,640.08 -2.7816515482,53.8066031939,640.08 -2.7870676238,53.8078127308,640.08 -2.7926653624,53.8086859834,640.08 -2.7983853004,53.8092136741,640.08 -2.8041666667,53.8093901962,640.08 + + + + +
+ + EGR313 SCAMPTON + A circle, 5 NM radius, centred at 531828N 0003303W
Upper limit: 9500 FT MSL
Lower limit: SFC
Class: Contact: Information on activation status may be obtained from Waddington ATC, Tel: 01522-727451/727452, or by radio to Waddington Zone on 119.500 MHz/232.700 MHz.

Non-radio aircraft may be able to obtain a pre-flight clearance by telephone. Radio equipped aircraft may request an in-flight clearance to enter EGR313 from Waddington Zone on 119.500/232.700 MHz.

SI 2023/879.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5508333332999999,53.3909816953,2895.6 -0.5599365630000001,53.3908032038,2895.6 -0.5690005838,53.3902684981,2895.6 -0.5779863586,53.389379881,2895.6 -0.5868551933,53.38814117969999,2895.6 -0.595568906,53.38655772839999,2895.6 -0.6040899937999999,53.38463634539999,2895.6 -0.6123817972,53.382385303,2895.6 -0.6204086597,53.3798142914,2895.6 -0.6281360829,53.3769343765,2895.6 -0.6355308768,53.3737579512,2895.6 -0.6425613032,53.3702986815,2895.6 -0.6491972133,53.366571447,2895.6 -0.6554101771,53.3625922757,2895.6 -0.6611736056,53.3583782744,2895.6 -0.6664628642,53.3539475544,2895.6 -0.6712553778,53.34931915249999,2895.6 -0.6755307254,53.3445129487,2895.6 -0.6792707268,53.33954958,2895.6 -0.6824595172,53.3344503507,2895.6 -0.6850836134,53.3292371409,2895.6 -0.687131968,53.3239323115,2895.6 -0.6885960136,53.3185586082,2895.6 -0.6894696963,53.3131390634,2895.6 -0.6897494974,53.3076968973,2895.6 -0.6894344449000001,53.3022554181,2895.6 -0.688526114,53.29683792239999,2895.6 -0.687028616,53.2914675952,2895.6 -0.6849485775,53.2861674113,2895.6 -0.6822951079,53.2809600368,2895.6 -0.6790797571,53.2758677328,2895.6 -0.6753164628,53.2709122608,2895.6 -0.6710214883,53.2661147902,2895.6 -0.6662133499,53.2614958084,2895.6 -0.6609127355,53.2570750343,2895.6 -0.6551424149,53.25287133449999,2895.6 -0.6489271405,53.2489026439,2895.6 -0.6422935407,53.2451858903,2895.6 -0.6352700061,53.2417369221,2895.6 -0.6278865675999999,53.2385704427,2895.6 -0.6201747691,53.23569994799999,2895.6 -0.6121675334,53.2331376696,2895.6 -0.6038990228,53.230894524,2895.6 -0.5954044954,53.22898006629999,2895.6 -0.5867201563,53.22740245039999,2895.6 -0.5778830057,53.22616839459999,2895.6 -0.5689306834,53.22528315380001,2895.6 -0.5599013112,53.2247504972,2895.6 -0.5508333332999999,53.22457269260001,2895.6 -0.5417653554,53.2247504972,2895.6 -0.5327359832,53.22528315380001,2895.6 -0.5237836608999999,53.22616839459999,2895.6 -0.5149465103,53.22740245039999,2895.6 -0.5062621713,53.22898006629999,2895.6 -0.4977676438999999,53.230894524,2895.6 -0.4894991333000001,53.2331376696,2895.6 -0.4814918975,53.23569994799999,2895.6 -0.473780099,53.2385704427,2895.6 -0.4663966606,53.2417369221,2895.6 -0.459373126,53.2451858903,2895.6 -0.4527395262,53.2489026439,2895.6 -0.4465242516999999,53.25287133449999,2895.6 -0.4407539310999999,53.2570750343,2895.6 -0.4354533168,53.2614958084,2895.6 -0.4306451783,53.2661147902,2895.6 -0.4263502038,53.2709122608,2895.6 -0.4225869096,53.2758677328,2895.6 -0.4193715588,53.2809600368,2895.6 -0.4167180891,53.2861674113,2895.6 -0.4146380506,53.2914675952,2895.6 -0.4131405527,53.29683792239999,2895.6 -0.4122322218,53.3022554181,2895.6 -0.4119171693,53.3076968973,2895.6 -0.4121969703,53.3131390634,2895.6 -0.413070653,53.3185586082,2895.6 -0.4145346987,53.3239323115,2895.6 -0.4165830533,53.3292371409,2895.6 -0.4192071494,53.3344503507,2895.6 -0.4223959399,53.33954958,2895.6 -0.4261359411999999,53.3445129487,2895.6 -0.4304112889,53.34931915249999,2895.6 -0.4352038024,53.3539475544,2895.6 -0.4404930611,53.3583782744,2895.6 -0.4462564895,53.3625922757,2895.6 -0.4524694533,53.366571447,2895.6 -0.4591053634,53.3702986815,2895.6 -0.4661357899,53.3737579512,2895.6 -0.4735305838,53.3769343765,2895.6 -0.481258007,53.3798142914,2895.6 -0.4892848694,53.382385303,2895.6 -0.4975766729,53.38463634539999,2895.6 -0.5060977607,53.38655772839999,2895.6 -0.5148114733,53.38814117969999,2895.6 -0.5236803081,53.389379881,2895.6 -0.5326660828999999,53.3902684981,2895.6 -0.5417301037,53.3908032038,2895.6 -0.5508333332999999,53.3909816953,2895.6 + + + + +
+ + EGR322 WYLFA + A circle, 2 NM radius, centred at 532458N 0042852W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted at a height of not less than 2000 FT above ground level whilst operating under and in accordance with a clearance from the air traffic control unit at RAF Valley.

Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Wylfa, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4812194444,53.4493672106,640.08 -4.4869518094,53.4491906797,640.08 -4.4926232685,53.44866296239999,640.08 -4.4981735678,53.4477896656,640.08 -4.5035437489,53.4465800672,640.08 -4.5086767801,53.445047017,640.08 -4.5135181648,53.4432067994,640.08 -4.5180165232,53.4410789594,640.08 -4.5221241391,53.4386860935,640.08 -4.5257974674,53.4360536087,640.08 -4.5289975955,53.43320945160001,640.08 -4.531690655,53.4301838097,640.08 -4.5338481782,53.4270087905,640.08 -4.5354473967,53.42371807930001,640.08 -4.5364714781,53.4203465809,640.08 -4.5369096997,53.41693004890001,640.08 -4.5367575564,53.4135047057,640.08 -4.5360168024,53.4101068585,640.08 -4.5346954268,53.4067725146,640.08 -4.532807563,53.4035370001,640.08 -4.5303733337,53.4004345861,640.08 -4.5274186328,53.39749812660001,640.08 -4.5239748471,53.3947587118,640.08 -4.5200785209,53.3922453397,640.08 -4.5157709669,53.389984611,640.08 -4.5110978279,53.38800044830001,640.08 -4.5061085937,53.3863138446,640.08 -4.5008560783,53.3849426423,640.08 -4.4953958637,53.3839013458,640.08 -4.4897857142,53.3832009688,640.08 -4.4840849692,53.3828489187,640.08 -4.4783539196,53.3828489187,640.08 -4.4726531746,53.3832009688,640.08 -4.4670430252,53.3839013458,640.08 -4.4615828106,53.3849426423,640.08 -4.4563302952,53.3863138446,640.08 -4.451341061,53.38800044830001,640.08 -4.4466679219,53.389984611,640.08 -4.442360368,53.3922453397,640.08 -4.4384640418,53.3947587118,640.08 -4.4350202561,53.39749812660001,640.08 -4.4320655552,53.4004345861,640.08 -4.4296313259,53.4035370001,640.08 -4.4277434621,53.4067725146,640.08 -4.4264220865,53.4101068585,640.08 -4.4256813325,53.4135047057,640.08 -4.4255291891,53.41693004890001,640.08 -4.4259674108,53.4203465809,640.08 -4.4269914922,53.42371807930001,640.08 -4.4285907107,53.4270087905,640.08 -4.4307482339,53.4301838097,640.08 -4.4334412934,53.43320945160001,640.08 -4.4366414215,53.4360536087,640.08 -4.4403147498,53.4386860935,640.08 -4.4444223657,53.4410789594,640.08 -4.4489207241,53.4432067994,640.08 -4.4537621088,53.445047017,640.08 -4.45889514,53.4465800672,640.08 -4.4642653211,53.4477896656,640.08 -4.4698156203,53.44866296239999,640.08 -4.4754870795,53.4491906797,640.08 -4.4812194444,53.4493672106,640.08 + + + + +
+ + EGR413 SELLAFIELD + A circle, 2 NM radius, centred at 542505N 0032944W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sellafield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4955555556,54.451331069,609.6 -3.5014269937,54.4511545625,609.6 -3.5072360431,54.4506269186,609.6 -3.5129209825,54.44975374380001,609.6 -3.5184214188,54.4485443153,609.6 -3.5236789329,54.4470114824,609.6 -3.5286377032,54.4451715284,609.6 -3.5332451019,54.44304399690001,609.6 -3.537452255,54.4406514827,609.6 -3.5412145619,54.4380193906,609.6 -3.5444921685,54.43517566460001,609.6 -3.5472503885,54.4321504892,609.6 -3.5494600685,54.4289759681,609.6 -3.5510978936,54.4256857826,609.6 -3.5521466295,54.42231483260001,609.6 -3.5525953007,54.4188988665,609.6 -3.5524392998,54.415474101,609.6 -3.551680431,54.4120768371,609.6 -3.5503268838,54.4087430754,609.6 -3.5483931406,54.4055081352,609.6 -3.5458998173,54.40240628039999,609.6 -3.54287344,54.399470358,609.6 -3.5393461593,54.3967314511,609.6 -3.535355407,54.3942185508,609.6 -3.5309434975,54.3919582512,609.6 -3.5261571785,54.3899744688,609.6 -3.5210471366,54.38828819099999,609.6 -3.5156674621,54.3869172556,609.6 -3.5100750787,54.3858761629,609.6 -3.5043291446,54.3851759235,609.6 -3.4984904303,54.3848239427,609.6 -3.4926206808,54.3848239427,609.6 -3.4867819665,54.3851759235,609.6 -3.4810360324,54.3858761629,609.6 -3.475443649,54.3869172556,609.6 -3.470063974499999,54.38828819099999,609.6 -3.4649539326,54.3899744688,609.6 -3.4601676136,54.3919582512,609.6 -3.4557557041,54.3942185508,609.6 -3.4517649518,54.3967314511,609.6 -3.4482376711,54.399470358,609.6 -3.4452112938,54.40240628039999,609.6 -3.4427179705,54.4055081352,609.6 -3.4407842274,54.4087430754,609.6 -3.4394306801,54.4120768371,609.6 -3.4386718113,54.415474101,609.6 -3.4385158104,54.4188988665,609.6 -3.4389644816,54.42231483260001,609.6 -3.4400132175,54.4256857826,609.6 -3.4416510426,54.4289759681,609.6 -3.443860722600001,54.4321504892,609.6 -3.4466189426,54.43517566460001,609.6 -3.4498965493,54.4380193906,609.6 -3.4536588561,54.4406514827,609.6 -3.4578660092,54.44304399690001,609.6 -3.4624734079,54.4451715284,609.6 -3.4674321783,54.4470114824,609.6 -3.4726896923,54.4485443153,609.6 -3.478190128700001,54.44975374380001,609.6 -3.483875068,54.4506269186,609.6 -3.4896841174,54.4511545625,609.6 -3.4955555556,54.451331069,609.6 + + + + +
+ + EGR444 HEYSHAM + A circle, 2 NM radius, centred at 540147N 0025452W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Heysham, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Microlight access to Middleton Sands obtained from BMAA head office.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.914422222199999,54.06309155930001,609.6 -2.9202387654,54.0629150434,609.6 -2.9259935051,54.0623873713,609.6 -2.931625299399999,54.06151414950001,609.6 -2.9370743215,54.0603046557,609.6 -2.9422826999,54.0587717391,609.6 -2.9471951361,54.05693168370001,609.6 -2.9517594948,54.0548040333,609.6 -2.955927359,54.0524113837,609.6 -2.9596545448,54.0497791404,609.6 -2.9629015698,54.04693524820001,609.6 -2.9656340704,54.0439098929,609.6 -2.9678231638,54.0407351798,609.6 -2.9694457509,54.03744479140001,609.6 -2.970484756,54.0340736299,609.6 -2.9709293033,54.03065744530001,609.6 -2.9707748258,54.02723245669999,609.6 -2.9700231078,54.0238349675,609.6 -2.9686822598,54.0205009808,609.6 -2.9667666265,54.0172658186,609.6 -2.9642966289,54.0141637476,609.6 -2.9612985437,54.0112276176,609.6 -2.957804219899999,54.0084885142,609.6 -2.9538507391,54.0059754314,609.6 -2.9494800202,54.0037149657,609.6 -2.9447383748,54.0017310361,609.6 -2.9396760171,54.0000446322,609.6 -2.9343465338,53.9986735935,609.6 -2.9288063188,53.99763242189999,609.6 -2.9231139803,53.9969321292,609.6 -2.9173297239,53.9965801216,609.6 -2.9115147206,53.9965801216,609.6 -2.9057304642,53.9969321292,609.6 -2.9000381256,53.99763242189999,609.6 -2.8944979107,53.9986735935,609.6 -2.8891684273,54.0000446322,609.6 -2.8841060697,54.0017310361,609.6 -2.879364424299999,54.0037149657,609.6 -2.8749937053,54.0059754314,609.6 -2.8710402245,54.0084885142,609.6 -2.8675459008,54.0112276176,609.6 -2.8645478155,54.0141637476,609.6 -2.862077817999999,54.0172658186,609.6 -2.8601621846,54.0205009808,609.6 -2.8588213367,54.0238349675,609.6 -2.8580696187,54.02723245669999,609.6 -2.8579151412,54.03065744530001,609.6 -2.8583596884,54.0340736299,609.6 -2.8593986936,54.03744479140001,609.6 -2.8610212806,54.0407351798,609.6 -2.8632103741,54.0439098929,609.6 -2.8659428747,54.04693524820001,609.6 -2.8691898996,54.0497791404,609.6 -2.8729170854,54.0524113837,609.6 -2.8770849496,54.0548040333,609.6 -2.8816493083,54.05693168370001,609.6 -2.8865617445,54.0587717391,609.6 -2.8917701229,54.0603046557,609.6 -2.897219145,54.06151414950001,609.6 -2.9028509393,54.0623873713,609.6 -2.908605679,54.0629150434,609.6 -2.914422222199999,54.06309155930001,609.6 + + + + +
+ + EGR445 BARROW IN FURNESS + A circle, 0.5 NM radius, centred at 540635N 0031410W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Barrow in Furness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2361111111,54.118041546,609.6 -3.2389617203,54.1178712153,609.6 -3.2416955575,54.1173672007,609.6 -3.2442006422,54.1165501481,609.6 -3.2463743796,54.11545352480001,609.6 -3.248127766,54.1141222467,609.6 -3.249389035,54.112610836,609.6 -3.2501065925,54.110981186,609.6 -3.250251122,54.10930002449999,609.6 -3.2498167752,54.1076361805,609.6 -3.2488214002,54.1060577659,609.6 -3.2473058003,54.104629388,609.6 -3.2453320547,54.10340950680001,609.6 -3.2429809723,54.1024480441,609.6 -3.2403487825,54.1017843434,609.6 -3.2375432,54.1014455622,609.6 -3.2346790222,54.1014455622,609.6 -3.2318734397,54.1017843434,609.6 -3.2292412499,54.1024480441,609.6 -3.2268901675,54.10340950680001,609.6 -3.2249164219,54.104629388,609.6 -3.223400821999999,54.1060577659,609.6 -3.2224054471,54.1076361805,609.6 -3.2219711003,54.10930002449999,609.6 -3.2221156297,54.110981186,609.6 -3.2228331872,54.112610836,609.6 -3.2240944562,54.1141222467,609.6 -3.2258478426,54.11545352480001,609.6 -3.22802158,54.1165501481,609.6 -3.2305266648,54.1173672007,609.6 -3.233260501899999,54.1178712153,609.6 -3.2361111111,54.118041546,609.6 + + + + +
+ + EGR446 HARTLEPOOL + A circle, 2 NM radius, centred at 543807N 0011049W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hartlepool, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight at a height of not less than 1800 FT amsl whilst conducting an instrument approach procedure at Teesside International Airport.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1802777778,54.66855208879999,609.6 -1.1861805046,54.6683755875,609.6 -1.192020509,54.6678479593,609.6 -1.1977357397,54.66697481050001,609.6 -1.2032654807,54.6657654184,609.6 -1.2085510006,54.66423263189999,609.6 -1.2135361801,54.6623927343,609.6 -1.2181681102,54.6602652688,609.6 -1.2223976566,54.6578728299,609.6 -1.2261799812,54.655240822,609.6 -1.2294750182,54.6523971884,609.6 -1.2322478972,54.649372113,609.6 -1.2344693105,54.64619769899999,609.6 -1.2361158203,54.6429076263,609.6 -1.2371701022,54.6395367943,609.6 -1.2376211234,54.63612095000001,609.6 -1.2374642539,54.6326963088,609.6 -1.2367013088,54.62929917059999,609.6 -1.2353405231,54.6259655344,609.6 -1.2333964576,54.62273071800001,609.6 -1.2308898392,54.6196289839,609.6 -1.2278473362,54.6166931775,609.6 -1.224301271,54.61395438029999,609.6 -1.2202892752,54.611441582,609.6 -1.2158538885,54.6091813752,609.6 -1.2110421072,54.60719767500001,609.6 -1.2059048872,54.6055114677,609.6 -1.2004966058,54.6041405901,609.6 -1.1948744885,54.60309954139999,609.6 -1.189098007,54.6023993318,609.6 -1.1832282541,54.60204736599999,609.6 -1.1773273015,54.60204736599999,609.6 -1.1714575485,54.6023993318,609.6 -1.1656810671,54.60309954139999,609.6 -1.1600589498,54.6041405901,609.6 -1.1546506683,54.6055114677,609.6 -1.1495134483,54.60719767500001,609.6 -1.144701667,54.6091813752,609.6 -1.1402662803,54.611441582,609.6 -1.1362542845,54.61395438029999,609.6 -1.1327082194,54.6166931775,609.6 -1.1296657163,54.6196289839,609.6 -1.127159098,54.62273071800001,609.6 -1.1252150324,54.6259655344,609.6 -1.1238542467,54.62929917059999,609.6 -1.1230913017,54.6326963088,609.6 -1.1229344322,54.63612095000001,609.6 -1.1233854534,54.6395367943,609.6 -1.1244397352,54.6429076263,609.6 -1.126086245,54.64619769899999,609.6 -1.1283076584,54.649372113,609.6 -1.1310805374,54.6523971884,609.6 -1.1343755744,54.655240822,609.6 -1.138157899,54.6578728299,609.6 -1.1423874453,54.6602652688,609.6 -1.1470193755,54.6623927343,609.6 -1.1520045549,54.66423263189999,609.6 -1.1572900749,54.6657654184,609.6 -1.1628198159,54.66697481050001,609.6 -1.1685350466,54.6678479593,609.6 -1.1743750509,54.6683755875,609.6 -1.1802777778,54.66855208879999,609.6 + + + + +
+ + EGR515 HUNTERSTON + A circle, 2 NM radius, centred at 554317N 0045338W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hunterston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8938888889,55.7546572369,609.6 -4.8999545473,55.75448076140001,609.6 -4.9059557454,55.7539532102,609.6 -4.9118287131,55.7530801894,609.6 -4.9175110532,55.751870976,609.6 -4.9229424086,55.75033841810001,609.6 -4.9280651075,55.748498798,609.6 -4.9328247789,55.7463716576,609.6 -4.9371709319,55.74397958980001,609.6 -4.941057492,55.7413479969,609.6 -4.9444432906,55.7385048196,609.6 -4.9472924991,55.7354802387,609.6 -4.9495750068,55.7323063534,609.6 -4.9512667358,55.7290168396,609.6 -4.9523498915,55.7256465915,609.6 -4.9528131451,55.72223135069999,609.6 -4.9526517473,55.71880732649999,609.6 -4.9518675721,55.7154108119,609.6 -4.9504690896,55.71207779910001,609.6 -4.9484712699,55.7088435984,609.6 -4.9458954179,55.7057424646,609.6 -4.9427689426,55.7028072354,609.6 -4.9391250617,55.7000689844,609.6 -4.9350024464,55.697556694,609.6 -4.9304448098,55.6952969494,609.6 -4.9255004428,55.6933136592,609.6 -4.9202217032,55.6916278036,609.6 -4.9146644628,55.6902572139,609.6 -4.908887519,55.6892163852,609.6 -4.9029519762,55.6885163242,609.6 -4.8969206031,55.6881644332,609.6 -4.8908571746,55.6881644332,609.6 -4.8848258016,55.6885163242,609.6 -4.8788902587,55.6892163852,609.6 -4.873113315,55.6902572139,609.6 -4.8675560746,55.6916278036,609.6 -4.862277335,55.6933136592,609.6 -4.8573329679,55.6952969494,609.6 -4.8527753314,55.697556694,609.6 -4.8486527161,55.7000689844,609.6 -4.8450088351,55.7028072354,609.6 -4.8418823598,55.7057424646,609.6 -4.8393065079,55.7088435984,609.6 -4.8373086881,55.71207779910001,609.6 -4.8359102057,55.7154108119,609.6 -4.8351260305,55.71880732649999,609.6 -4.8349646327,55.72223135069999,609.6 -4.8354278863,55.7256465915,609.6 -4.836511042,55.7290168396,609.6 -4.838202771,55.7323063534,609.6 -4.8404852787,55.7354802387,609.6 -4.8433344872,55.7385048196,609.6 -4.8467202857,55.7413479969,609.6 -4.8506068459,55.74397958980001,609.6 -4.8549529988,55.7463716576,609.6 -4.8597126703,55.748498798,609.6 -4.8648353692,55.75033841810001,609.6 -4.8702667246,55.751870976,609.6 -4.8759490647,55.7530801894,609.6 -4.8818220324,55.7539532102,609.6 -4.8878232305,55.75448076140001,609.6 -4.8938888889,55.7546572369,609.6 + + + + +
+ + EGR516 TORNESS + A circle, 2 NM radius, centred at 555806N 0022431W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Torness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4084777778,56.0015392269,640.08 -2.4145820483,56.0013627571,640.08 -2.4206214466,56.00083522309999,640.08 -2.4265317954,55.9999622309,640.08 -2.4322502988,55.99875305729999,640.08 -2.4377162144,55.9972205504,640.08 -2.4428715028,55.9953809923,640.08 -2.4476614461,55.9932539246,640.08 -2.4520352321,55.9908619399,640.08 -2.4559464934,55.98823044,640.08 -2.4593537998,55.985387365,640.08 -2.4622210959,55.982362895,640.08 -2.4645180807,55.9791891284,640.08 -2.4662205246,55.9758997402,640.08 -2.4673105215,55.9725296235,640.08 -2.4677766727,55.9691145185,640.08 -2.4676142006,55.9656906333,640.08 -2.4668249932,55.9622942594,640.08 -2.4654175764,55.95896138730001,640.08 -2.4634070172,55.9557273257,640.08 -2.4608147578,55.9526263276,640.08 -2.4576683825,55.94969122879999,640.08 -2.4540013212,55.9469531015,640.08 -2.4498524916,55.94444092610001,640.08 -2.4452658848,55.94218128619999,640.08 -2.4402900985,55.9401980889,640.08 -2.4349778227,55.938512313,640.08 -2.4293852834,55.9371417886,640.08 -2.4235716504,55.9361010098,640.08 -2.4175984149,55.9354009824,640.08 -2.4115287429,55.9350491084,640.08 -2.4054268127,55.9350491084,640.08 -2.3993571407,55.9354009824,640.08 -2.3933839051,55.9361010098,640.08 -2.3875702722,55.9371417886,640.08 -2.3819777329,55.938512313,640.08 -2.376665457,55.9401980889,640.08 -2.3716896707,55.94218128619999,640.08 -2.367103064,55.94444092610001,640.08 -2.3629542344,55.9469531015,640.08 -2.3592871731,55.94969122879999,640.08 -2.3561407978,55.9526263276,640.08 -2.3535485383,55.9557273257,640.08 -2.3515379792,55.95896138730001,640.08 -2.3501305624,55.9622942594,640.08 -2.3493413549,55.9656906333,640.08 -2.3491788829,55.9691145185,640.08 -2.3496450341,55.9725296235,640.08 -2.350735031,55.9758997402,640.08 -2.3524374749,55.9791891284,640.08 -2.3547344596,55.982362895,640.08 -2.3576017558,55.985387365,640.08 -2.3610090622,55.98823044,640.08 -2.3649203235,55.9908619399,640.08 -2.3692941094,55.9932539246,640.08 -2.3740840528,55.9953809923,640.08 -2.3792393411,55.9972205504,640.08 -2.3847052568,55.99875305729999,640.08 -2.3904237602,55.9999622309,640.08 -2.3963341089,56.00083522309999,640.08 -2.4023735073,56.0013627571,640.08 -2.4084777778,56.0015392269,640.08 + + + + +
+ + EGR603 ROSYTH + A circle, 0.5 NM radius, centred at 560147N 0032703W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted within the route notified as the Kelty Lane for the purpose of making an approach to land at, or a departure from, Edinburgh Airport.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.450833333299999,56.0380389069,609.6 -3.4538238226,56.0378686278,609.6 -3.4566918046,56.0373647659,609.6 -3.4593197998,56.036547962,609.6 -3.4616001767,56.0354516743,609.6 -3.4634395644,56.0341208066,609.6 -3.464762678,56.0326098656,609.6 -3.4655153966,56.0309807265,609.6 -3.4656669719,56.0293000971,609.6 -3.465211276,56.0276367846,609.6 -3.4641670394,56.02605887879999,609.6 -3.4625770722,56.0246309652,609.6 -3.4605065022,56.0234114834,609.6 -3.4580401027,56.02245033740001,609.6 -3.4552788212,56.0217868563,609.6 -3.4523356513,56.0214481874,609.6 -3.4493310153,56.0214481874,609.6 -3.446387845499999,56.0217868563,609.6 -3.443626564,56.02245033740001,609.6 -3.4411601645,56.0234114834,609.6 -3.4390895945,56.0246309652,609.6 -3.4374996273,56.02605887879999,609.6 -3.4364553907,56.0276367846,609.6 -3.4359996948,56.0293000971,609.6 -3.4361512701,56.0309807265,609.6 -3.436903988700001,56.0326098656,609.6 -3.4382271022,56.0341208066,609.6 -3.44006649,56.0354516743,609.6 -3.4423468668,56.036547962,609.6 -3.4449748621,56.0373647659,609.6 -3.447842844,56.0378686278,609.6 -3.450833333299999,56.0380389069,609.6 + + + + +
+ + EGR610A THE HIGHLANDS + 583000N 0033902W -
582828N 0033815W -
582356N 0032847W -
580345N 0041248W -
580300N 0043000W -
580000N 0043700W -
574700N 0042500W -
573900N 0043000W -
573800N 0044500W -
573000N 0043800W -
571800N 0045200W -
571100N 0045300W -
570900N 0050000W -
570000N 0050200W -
565400N 0050500W -
565600N 0054700W -
571300N 0053500W -
575000N 0054300W -
580000N 0051500W -
583000N 0044900W -
583000N 0043000W -
582500N 0043000W -
583000N 0042000W -
583000N 0033902W
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Military Airspace Management Cell - Low Flying (MAMC LF) at RAF (U) Swanwick, Tel: 01489-443100.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.6505555556,58.5,1524 -4.3333333333,58.5,1524 -4.5,58.4166666667,1524 -4.5,58.5,1524 -4.8166666667,58.5,1524 -5.25,58.00000000000001,1524 -5.7166666667,57.8333333333,1524 -5.5833333333,57.2166666667,1524 -5.783333333299999,56.9333333333,1524 -5.0833333333,56.9,1524 -5.0333333333,57,1524 -5,57.15,1524 -4.8833333333,57.1833333333,1524 -4.8666666667,57.3,1524 -4.6333333333,57.49999999999999,1524 -4.75,57.6333333333,1524 -4.5,57.65,1524 -4.4166666667,57.7833333333,1524 -4.6166666667,58.00000000000001,1524 -4.5,58.05,1524 -4.2133333333,58.0625,1524 -3.4798583333,58.39885,1524 -3.6375,58.47444444440001,1524 -3.6505555556,58.5,1524 + + + + +
+ + EGR610B THE HIGHLANDS + 575000N 0054300W -
574004N 0054050W -
573840N 0055739W -
570000N 0055644W -
570000N 0061504W -
574715N 0061637W -
575000N 0054300W
Upper limit: 5000 FT MSL
Lower limit: 750 FT MSL
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,1524 -6.2769444444,57.7875,1524 -6.2511111111,57,1524 -5.9455555556,57,1524 -5.960833333300001,57.6444444444,1524 -5.680555555599999,57.6677777778,1524 -5.7166666667,57.8333333333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,228.6 -6.2769444444,57.7875,228.6 -6.2511111111,57,228.6 -5.9455555556,57,228.6 -5.960833333300001,57.6444444444,228.6 -5.680555555599999,57.6677777778,228.6 -5.7166666667,57.8333333333,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,228.6 -6.2769444444,57.7875,228.6 -6.2769444444,57.7875,1524 -5.7166666667,57.8333333333,1524 -5.7166666667,57.8333333333,228.6 + + + + + + relativeToGround + + + relativeToGround + + -6.2769444444,57.7875,228.6 -6.2511111111,57,228.6 -6.2511111111,57,1524 -6.2769444444,57.7875,1524 -6.2769444444,57.7875,228.6 + + + + + + relativeToGround + + + relativeToGround + + -6.2511111111,57,228.6 -5.9455555556,57,228.6 -5.9455555556,57,1524 -6.2511111111,57,1524 -6.2511111111,57,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.9455555556,57,228.6 -5.960833333300001,57.6444444444,228.6 -5.960833333300001,57.6444444444,1524 -5.9455555556,57,1524 -5.9455555556,57,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.960833333300001,57.6444444444,228.6 -5.680555555599999,57.6677777778,228.6 -5.680555555599999,57.6677777778,1524 -5.960833333300001,57.6444444444,1524 -5.960833333300001,57.6444444444,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.680555555599999,57.6677777778,228.6 -5.7166666667,57.8333333333,228.6 -5.7166666667,57.8333333333,1524 -5.680555555599999,57.6677777778,1524 -5.680555555599999,57.6677777778,228.6 + + + + + +
+ + EGR610C THE HIGHLANDS + 582218N 0033224W -
581434N 0031929W -
581121N 0032654W -
581900N 0033940W -
582218N 0033224W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.54,58.3716666667,609.6 -3.6611111111,58.3166666667,609.6 -3.4483333333,58.1891666667,609.6 -3.3247222222,58.24277777780001,609.6 -3.54,58.3716666667,609.6 + + + + +
+ + EGR610D THE HIGHLANDS + 574900N 0040606W -
574500N 0040254W -
574234N 0041056W -
573900N 0043000W -
574700N 0042500W -
574900N 0040606W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1016666667,57.8166666667,609.6 -4.4166666667,57.7833333333,609.6 -4.5,57.65,609.6 -4.1822222222,57.7094444444,609.6 -4.0483333333,57.75000000000001,609.6 -4.1016666667,57.8166666667,609.6 + + + + +
+ + EGR704 BALMORAL + A circle, 1 NM radius, centred at 570227N 0031349W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
Any aircraft operated by or on behalf of Police Scotland;
any aircraft operated by or on behalf of the Scottish Air Ambulance Service;
any aircraft operated by or on behalf of the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;
any aircraft operated by or on behalf of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —

Operated by a member of the Royal Family, or landing in the grounds of Balmoral at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.

SI 2019/1321.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2302777778,57.0574639676,1066.8 -3.234721726400001,57.0572866625,1066.8 -3.2390708352,57.05675853110001,1066.8 -3.2432322962,57.0558908441,1066.8 -3.2471173212,57.0547021176,1066.8 -3.250643042,57.05321771640001,1066.8 -3.2537342822,57.0514693109,1066.8 -3.2563251621,57.04949419960001,1066.8 -3.2583605024,57.04733451079999,1066.8 -3.2597969969,57.0450363023,1066.8 -3.260604129,57.0426485773,1066.8 -3.2607648138,57.0402222381,1066.8 -3.2602757524,57.0378090004,1066.8 -3.2591474911,57.0354602907,1066.8 -3.2574041866,57.033226151,1066.8 -3.2550830817,57.0311541735,1066.8 -3.2522337042,57.0292884884,1066.8 -3.2489168064,57.02766882600001,1066.8 -3.2452030682,57.02632967280001,1066.8 -3.2411715924,57.025299539,1066.8 -3.2369082222,57.0246003539,1066.8 -3.232503719,57.0242470008,1066.8 -3.2280518366,57.0242470008,1066.8 -3.223647333400001,57.0246003539,1066.8 -3.2193839632,57.025299539,1066.8 -3.215352487300001,57.02632967280001,1066.8 -3.2116387492,57.02766882600001,1066.8 -3.2083218513,57.0292884884,1066.8 -3.2054724739,57.0311541735,1066.8 -3.203151369,57.033226151,1066.8 -3.2014080645,57.0354602907,1066.8 -3.2002798032,57.0378090004,1066.8 -3.1997907417,57.0402222381,1066.8 -3.1999514266,57.0426485773,1066.8 -3.2007585587,57.0450363023,1066.8 -3.2021950531,57.04733451079999,1066.8 -3.2042303935,57.04949419960001,1066.8 -3.2068212734,57.0514693109,1066.8 -3.2099125136,57.05321771640001,1066.8 -3.2134382344,57.0547021176,1066.8 -3.2173232594,57.0558908441,1066.8 -3.2214847204,57.05675853110001,1066.8 -3.2258338292,57.0572866625,1066.8 -3.2302777778,57.0574639676,1066.8 + + + + +
+ + EGR705 BIRKHALL + A circle, 1 NM radius, centred at 570144N 0030427W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
Any aircraft operated by, or on behalf of, Police Scotland;
any aircraft operated by, or on behalf of, the Scottish Air Ambulance Service;
any aircraft operated by, or on behalf of, the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;
any aircraft operated by, or on behalf of, The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —

Operated by a member of the Royal Family,
or landing in the grounds of Birkhall at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.

SI 2019/1320.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0741666667,57.04551955510001,1066.8 -3.078609189,57.04534224970001,1066.8 -3.0829569019,57.0448141174,1066.8 -3.087117027500001,57.0439464289,1066.8 -3.091000805899999,57.04275770030001,1066.8 -3.0945253956,57.04127329649999,1066.8 -3.0976156443,57.0395248879,1066.8 -3.1002056935,57.037549773,1066.8 -3.1022403815,57.0353900803,1066.8 -3.1036764159,57.0330918675,1066.8 -3.10448329,57.030704138,1066.8 -3.1046439242,57.0282777942,1066.8 -3.1041550205,57.02586455180001,1066.8 -3.1030271218,57.0235158375,1066.8 -3.1012843771,57.0212816933,1066.8 -3.0989640172,57.0192097116,1066.8 -3.0961155538,57.01734402270001,1066.8 -3.0927997198,57.01572435689999,1066.8 -3.0890871725,57.01438520090001,1066.8 -3.0850569891,57.0133550649,1066.8 -3.0807949857,57.0126558784,1066.8 -3.076391894299999,57.01230252449999,1066.8 -3.071941439,57.01230252449999,1066.8 -3.0675383477,57.0126558784,1066.8 -3.0632763442,57.0133550649,1066.8 -3.0592461609,57.01438520090001,1066.8 -3.0555336136,57.01572435689999,1066.8 -3.0522177795,57.01734402270001,1066.8 -3.0493693162,57.0192097116,1066.8 -3.0470489562,57.0212816933,1066.8 -3.0453062115,57.0235158375,1066.8 -3.0441783129,57.02586455180001,1066.8 -3.0436894092,57.0282777942,1066.8 -3.0438500434,57.030704138,1066.8 -3.044656917400001,57.0330918675,1066.8 -3.0460929518,57.0353900803,1066.8 -3.0481276399,57.037549773,1066.8 -3.050717689,57.0395248879,1066.8 -3.0538079377,57.04127329649999,1066.8 -3.0573325274,57.04275770030001,1066.8 -3.0612163059,57.0439464289,1066.8 -3.0653764314,57.0448141174,1066.8 -3.0697241443,57.04534224970001,1066.8 -3.0741666667,57.04551955510001,1066.8 + + + + +
+ + EGRU001A LAND'S END + A circle, 2 NM radius, centred at 500610N 0054014W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6705805556,50.1360027382,609.6 -5.6759075942,50.13582612260001,609.6 -5.6811780483,50.135298152,609.6 -5.6863359382,50.1344244342,609.6 -5.691326487,50.1332142493,609.6 -5.6960967056,50.13168045030001,609.6 -5.7005959583,50.1298393258,609.6 -5.7047765024,50.12771042579999,609.6 -5.708593996199999,50.1253163537,609.6 -5.7120079707,50.1226825245,609.6 -5.714982258,50.1198368943,609.6 -5.717485374200001,50.1168096619,609.6 -5.7194908511,50.1136329477,609.6 -5.7209775143,50.1103404517,609.6 -5.7219297036,50.1069670951,609.6 -5.7223374351,50.1035486495,609.6 -5.7221965023,50.1001213569,609.6 -5.7215085159,50.0967215454,609.6 -5.720280881800001,50.09338524439999,609.6 -5.718526717599999,50.0901478028,609.6 -5.7162647094,50.087043515,609.6 -5.713518909699999,50.0841052587,609.6 -5.7103184794,50.0813641471,609.6 -5.706697376199999,50.07884920099999,609.6 -5.7026939937,50.0765870422,609.6 -5.6983507534,50.0746016133,609.6 -5.6937136564,50.0729139251,609.6 -5.6888317968,50.0715418357,609.6 -5.6837568442,50.0704998622,609.6 -5.6785424991,50.0697990282,609.6 -5.6732439281,50.0694467479,609.6 -5.667917183,50.0694467479,609.6 -5.662618612,50.0697990282,609.6 -5.6574042669,50.0704998622,609.6 -5.6523293143,50.0715418357,609.6 -5.6474474547,50.0729139251,609.6 -5.642810357700001,50.0746016133,609.6 -5.6384671174,50.0765870422,609.6 -5.634463734899999,50.07884920099999,609.6 -5.630842631700001,50.0813641471,609.6 -5.627642201399999,50.0841052587,609.6 -5.6248964017,50.087043515,609.6 -5.6226343935,50.0901478028,609.6 -5.6208802293,50.09338524439999,609.6 -5.6196525952,50.0967215454,609.6 -5.6189646089,50.1001213569,609.6 -5.6188236761,50.1035486495,609.6 -5.6192314075,50.1069670951,609.6 -5.6201835968,50.1103404517,609.6 -5.62167026,50.1136329477,609.6 -5.6236757369,50.1168096619,609.6 -5.626178853099999,50.1198368943,609.6 -5.6291531404,50.1226825245,609.6 -5.6325671149,50.1253163537,609.6 -5.6363846088,50.12771042579999,609.6 -5.640565152799999,50.1298393258,609.6 -5.6450644055,50.13168045030001,609.6 -5.649834624100001,50.1332142493,609.6 -5.6548251729,50.1344244342,609.6 -5.6599830628,50.135298152,609.6 -5.6652535169,50.13582612260001,609.6 -5.6705805556,50.1360027382,609.6 + + + + +
+ + EGRU001B LAND'S END RWY 02 + 500326N 0054128W -
500337N 0054215W -
500426N 0054148W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500414N 0054102W -
500326N 0054128W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6911472222,50.0572722222,609.6 -5.6838163611,50.0705099722,609.6 -5.688277730999999,50.0714098034,609.6 -5.6925948678,50.072565022,609.6 -5.696732583300001,50.0739661944,609.6 -5.7043,50.0602944444,609.6 -5.6911472222,50.0572722222,609.6 + + + + +
+ + EGRU001C LAND'S END RWY 20 + 500855N 0053919W -
500845N 0053832W -
500759N 0053857W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500808N 0053945W -
500855N 0053919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.655263888900001,50.1487388889,609.6 -5.662560111100001,50.135601,609.6 -5.6579724056,50.1350009132,609.6 -5.6534878727,50.13413688250001,609.6 -5.6491431944,50.133016,609.6 -5.642086111100001,50.1457166667,609.6 -5.655263888900001,50.1487388889,609.6 + + + + +
+ + EGRU001D LAND'S END RWY 07 + 500441N 0054420W -
500511N 0054441W -
500537N 0054314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500508N 0054254W -
500441N 0054420W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7388095556,50.0781908333,609.6 -5.7148789444,50.0854752222,609.6 -5.7171147379,50.0881153518,609.6 -5.7189715321,50.0908744357,609.6 -5.7204341389,50.09373,609.6 -5.744775305600001,50.0863204167,609.6 -5.7388095556,50.0781908333,609.6 + + + + +
+ + EGRU001E LAND'S END RWY 25 + 500738N 0053637W -
500708N 0053616W -
500650N 0053718W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500718N 0053741W -
500738N 0053637W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6103814444,50.1271384722,609.6 -5.6281196944,50.1217638889,609.6 -5.6256200098,50.1192229179,609.6 -5.6234872223,50.1165472972,609.6 -5.6217386667,50.1137588611,609.6 -5.6044106111,50.1190089444,609.6 -5.6103814444,50.1271384722,609.6 + + + + +
+ + EGRU001F LAND'S END RWY 11 + 500657N 0054430W -
500726N 0054411W -
500707N 0054258W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500637N 0054316W -
500657N 0054430W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7417068611,50.11570450000001,609.6 -5.7210458611,50.1101511389,609.6 -5.7197968384,50.11304867810001,609.6 -5.7181462876,50.1158619309,609.6 -5.7161076111,50.1185679444,609.6 -5.7363042222,50.1239965556,609.6 -5.7417068611,50.11570450000001,609.6 + + + + +
+ + EGRU001G LAND'S END RWY 29 + 500516N 0053607W -
500446N 0053627W -
500505N 0053737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500535N 0053716W -
500516N 0053607W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6019960278,50.08780683330001,609.6 -5.6210773611,50.0929611389,609.6 -5.6226464125,50.0901288342,609.6 -5.6246059681,50.087399098,609.6 -5.626939999999999,50.08479416669999,609.6 -5.6073946111,50.0795147222,609.6 -5.6019960278,50.08780683330001,609.6 + + + + +
+ + EGRU001H LAND'S END RWY 16 + 500843N 0054216W -
500855N 0054130W -
500806N 0054059W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500754N 0054146W -
500843N 0054216W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.704525,50.1452111111,609.6 -5.6961072222,50.1316766111,609.6 -5.691940084799999,50.1330387019,609.6 -5.6875986663,50.1341536005,609.6 -5.6831183889,50.1350122222,609.6 -5.6915305556,50.14854444440001,609.6 -5.704525,50.1452111111,609.6 + + + + +
+ + EGRU001I LAND'S END RWY 34 + 500334N 0053810W -
500322N 0053857W -
500413N 0053929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500425N 0053842W -
500334N 0053810W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.636175,50.0593444444,609.6 -5.6450833611,50.0737236667,609.6 -5.649245904,50.0723633887,609.6 -5.653581799,50.0712499565,609.6 -5.6580558056,50.0703924167,609.6 -5.649141666700001,50.0560111111,609.6 -5.636175,50.0593444444,609.6 + + + + +
+ + EGRU002A PENZANCE + A circle, 2 NM radius, centred at 500749N 0053050W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5139555556,50.1636886897,609.6 -5.5192856706,50.1635120748,609.6 -5.5245591683,50.1629841063,609.6 -5.5297200365,50.1621103922,609.6 -5.5347134667,50.1609002124,609.6 -5.539486439,50.15936641979999,609.6 -5.5439882886,50.157525303,609.6 -5.5481712449,50.1553964121,609.6 -5.5519909409,50.1530023503,609.6 -5.555406884,50.15036853260001,609.6 -5.5583828855,50.14752291489999,609.6 -5.5608874435,50.1444956961,609.6 -5.5628940747,50.1413189963,609.6 -5.5643815924,50.1380265155,609.6 -5.5653343275,50.1346531747,609.6 -5.5657422906,50.1312347453,609.6 -5.5656012729,50.1278074691,609.6 -5.5649128862,50.1244076743,609.6 -5.5636845407,50.12107138979999,609.6 -5.5619293619,50.1178339644,609.6 -5.5596660466,50.11472969239999,609.6 -5.5569186613,50.1117914512,609.6 -5.5537163839,50.10905035390001,609.6 -5.5500931917,50.106535421,609.6 -5.5460875004,50.10427327419999,609.6 -5.541741756,50.10228785589999,609.6 -5.5371019861,50.10060017679999,609.6 -5.532217313,50.0992280948,609.6 -5.5271394359,50.098186127,609.6 -5.5219220864,50.0974852968,609.6 -5.5166204626,50.0971330184,609.6 -5.5112906485,50.0971330184,609.6 -5.5059890247,50.0974852968,609.6 -5.5007716752,50.098186127,609.6 -5.4956937982,50.0992280948,609.6 -5.490809125,50.10060017679999,609.6 -5.4861693551,50.10228785589999,609.6 -5.4818236107,50.10427327419999,609.6 -5.4778179194,50.106535421,609.6 -5.4741947272,50.10905035390001,609.6 -5.4709924498,50.1117914512,609.6 -5.4682450646,50.11472969239999,609.6 -5.4659817493,50.1178339644,609.6 -5.4642265704,50.12107138979999,609.6 -5.4629982249,50.1244076743,609.6 -5.4623098382,50.1278074691,609.6 -5.4621688205,50.1312347453,609.6 -5.4625767836,50.1346531747,609.6 -5.4635295187,50.1380265155,609.6 -5.4650170364,50.1413189963,609.6 -5.4670236676,50.1444956961,609.6 -5.4695282256,50.14752291489999,609.6 -5.4725042271,50.15036853260001,609.6 -5.4759201702,50.1530023503,609.6 -5.4797398662,50.1553964121,609.6 -5.4839228226,50.157525303,609.6 -5.4884246721,50.15936641979999,609.6 -5.4931976444,50.1609002124,609.6 -5.4981910746,50.1621103922,609.6 -5.5033519428,50.1629841063,609.6 -5.5086254405,50.1635120748,609.6 -5.5139555556,50.1636886897,609.6 + + + + +
+ + EGRU002B PENZANCE RWY 08 + 500706N 0053454W -
500738N 0053503W -
500745N 0053357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to
500713N 0053348W -
500706N 0053454W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5817965278,50.11826600000001,609.6 -5.5633322778,50.1203276389,609.6 -5.5645434783,50.12322990009999,609.6 -5.5653429327,50.12619053510001,609.6 -5.5657240556,50.1291854444,609.6 -5.58417825,50.1271248889,609.6 -5.5817965278,50.11826600000001,609.6 + + + + +
+ + EGRU002C PENZANCE RWY 26 + 500833N 0052646W -
500801N 0052637W -
500754N 0052744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to
500826N 0052752W -
500833N 0052646W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.4460903889,50.1424680556,609.6 -5.46455675,50.1404263056,609.6 -5.4633515891,50.1375229498,609.6 -5.4625586488,50.13456158649999,609.6 -5.4621843333,50.1315663333,609.6 -5.4437078889,50.1336091944,609.6 -5.4460903889,50.1424680556,609.6 + + + + +
+ + EGRU003A CULDROSE + A circle, 2.5 NM radius, centred at 500507N 0051515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2540722222,50.1270222675,609.6 -5.2600465019,50.1268445494,609.6 -5.2659696794,50.1263129153,609.6 -5.271791093,50.1254319124,609.6 -5.2774609581,50.124209076,609.6 -5.282930796,50.1226548643,609.6 -5.2881538508,50.1207825685,609.6 -5.293085492,50.1186081982,609.6 -5.2976835968,50.1161503437,609.6 -5.3019089119,50.1134300161,609.6 -5.3057253884,50.1104704664,609.6 -5.3091004903,50.1072969857,609.6 -5.3120054703,50.1039366885,609.6 -5.3144156139,50.1004182793,609.6 -5.3163104478,50.0967718071,609.6 -5.3176739117,50.0930284076,609.6 -5.3184944912,50.08922003679999,609.6 -5.3187653125,50.0853791979,609.6 -5.3184841965,50.08153866340001,609.6 -5.3176536728,50.0777311953,609.6 -5.316280954,50.073989266,609.6 -5.3143778694,50.0703447816,609.6 -5.3119607606,50.06682881,609.6 -5.3090503379,50.06347131719999,609.6 -5.3056715012,50.06030091220001,609.6 -5.3018531249,50.0573446048,609.6 -5.2976278098,50.0546275756,609.6 -5.2930316047,50.0521729635,609.6 -5.2881036984,50.05000166889999,609.6 -5.2828860862,50.0481321775,609.6 -5.2774232136,50.04658040340001,609.6 -5.271761599,50.0453595547,609.6 -5.2659494404,50.0444800221,609.6 -5.2600362071,50.0439492907,609.6 -5.2540722222,50.0437718769,609.6 -5.2481082373,50.0439492907,609.6 -5.242195004,50.0444800221,609.6 -5.2363828454,50.0453595547,609.6 -5.2307212309,50.04658040340001,609.6 -5.2252583582,50.0481321775,609.6 -5.220040746,50.05000166889999,609.6 -5.2151128397,50.0521729635,609.6 -5.2105166346,50.0546275756,609.6 -5.2062913196,50.0573446048,609.6 -5.2024729432,50.06030091220001,609.6 -5.1990941066,50.06347131719999,609.6 -5.1961836839,50.06682881,609.6 -5.193766575,50.0703447816,609.6 -5.1918634905,50.073989266,609.6 -5.1904907716,50.0777311953,609.6 -5.1896602479,50.08153866340001,609.6 -5.1893791319,50.0853791979,609.6 -5.1896499532,50.08922003679999,609.6 -5.1904705327,50.0930284076,609.6 -5.1918339966,50.0967718071,609.6 -5.1937288306,50.1004182793,609.6 -5.1961389742,50.1039366885,609.6 -5.1990439541,50.1072969857,609.6 -5.202419056,50.1104704664,609.6 -5.2062355326,50.1134300161,609.6 -5.2104608476,50.1161503437,609.6 -5.2150589524,50.1186081982,609.6 -5.2199905936,50.1207825685,609.6 -5.2252136485,50.1226548643,609.6 -5.2306834863,50.124209076,609.6 -5.2363533515,50.1254319124,609.6 -5.2421747651,50.1263129153,609.6 -5.2480979426,50.1268445494,609.6 -5.2540722222,50.1270222675,609.6 + + + + +
+ + EGRU003B CULDROSE RWY 06 + 500339N 0051921W -
500408N 0051944W -
500423N 0051857W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500353N 0051837W -
500339N 0051921W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3224722222,50.0608,609.6 -5.3102815833,50.0648040278,609.6 -5.3124470945,50.067469965,609.6 -5.314308046,50.0702295787,609.6 -5.3158546667,50.0730684722,609.6 -5.3288083333,50.0688138889,609.6 -5.3224722222,50.0608,609.6 + + + + +
+ + EGRU003C CULDROSE RWY 24 + 500650N 0051129W -
500621N 0051106W -
500609N 0051142W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500637N 0051208W -
500650N 0051129W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1913138889,50.1138611111,609.6 -5.2022176389,50.11029775,609.6 -5.1995584017,50.10782339359999,609.6 -5.1971842309,50.10523193880001,609.6 -5.1951074722,50.1025369444,609.6 -5.1849694444,50.10585,609.6 -5.1913138889,50.1138611111,609.6 + + + + +
+ + EGRU003D CULDROSE RWY 11 + 500607N 0051959W -
500637N 0051939W -
500620N 0051838W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500550N 0051858W -
500607N 0051959W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3329861111,50.1018638889,609.6 -5.3160738056,50.0972953889,609.6 -5.3145814639,50.1001392694,609.6 -5.3127741935,50.1029065511,609.6 -5.3106613611,50.10558283329999,609.6 -5.3275583333,50.11014722219999,609.6 -5.3329861111,50.1018638889,609.6 + + + + +
+ + EGRU003E CULDROSE RWY 29 + 500408N 0051031W -
500338N 0051050W -
500355N 0051151W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500424N 0051132W -
500408N 0051031W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1752277778,50.0688777778,609.6 -5.19210275,50.0734629167,609.6 -5.1936019857,50.0706204565,609.6 -5.1954154024,50.06785489859999,609.6 -5.1975335278,50.0651806111,609.6 -5.1806444444,50.0605916667,609.6 -5.1752277778,50.0688777778,609.6 + + + + +
+ + EGRU003F CULDROSE RWY 18 + 500805N 0051538W -
500806N 0051448W -
500736N 0051447W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500737N 0051537W -
500805N 0051538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2606666667,50.1348166667,609.6 -5.26033425,50.1268269722,609.6 -5.2556702386,50.1270095639,609.6 -5.2509978848,50.1269752666,609.6 -5.2463415833,50.12672425,609.6 -5.2466861111,50.1350555556,609.6 -5.2606666667,50.1348166667,609.6 + + + + +
+ + EGRU003G CULDROSE RWY 36 + 500209N 0051433W -
500208N 0051524W -
500238N 0051525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500240N 0051435W -
500209N 0051433W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2425861111,50.03572222219999,609.6 -5.2429433056,50.0443929444,609.6 -5.2475654006,50.04398315030001,609.6 -5.2522213076,50.0437889397,609.6 -5.2568868333,50.0438113333,609.6 -5.2565416667,50.03548333330001,609.6 -5.2425861111,50.03572222219999,609.6 + + + + +
+ + EGRU004A PREDANNACK + A circle, 2 NM radius, centred at 500007N 0051354W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2317694444,50.0353338744,609.6 -5.2370853375,50.0351572562,609.6 -5.2423447648,50.03462927759999,609.6 -5.2474918642,50.0337555467,609.6 -5.2524719738,50.0325453435,609.6 -5.2572322156,50.0310115211,609.6 -5.2617220602,50.0291703683,609.6 -5.2658938646,50.0270414353,609.6 -5.2697033803,50.0246473257,609.6 -5.2731102226,50.0220134548,609.6 -5.2760782991,50.0191677788,609.6 -5.2785761915,50.0161404971,609.6 -5.2805774868,50.0129637305,609.6 -5.2820610542,50.0096711794,609.6 -5.2830112659,50.0062977655,609.6 -5.2834181582,50.0028792609,609.6 -5.283277533,49.99945190819999,609.6 -5.2825909971,49.9960520364,609.6 -5.2813659402,49.9927156753,609.6 -5.2796154522,49.98947817460001,609.6 -5.2773581795,49.9863738295,609.6 -5.2746181242,49.9834355182,609.6 -5.2714243858,49.9806943547,609.6 -5.2678108511,49.9781793605,609.6 -5.2638158332,49.9759171581,609.6 -5.2594816653,49.9739316906,609.6 -5.2548542522,49.9722439694,609.6 -5.2499825859,49.9708718529,609.6 -5.2449182283,49.9698298588,609.6 -5.2397147684,49.96912901090001,609.6 -5.2344272576,49.9687767236,609.6 -5.2291116313,49.9687767236,609.6 -5.2238241205,49.96912901090001,609.6 -5.2186206606,49.9698298588,609.6 -5.213556303,49.9708718529,609.6 -5.2086846367,49.9722439694,609.6 -5.2040572236,49.9739316906,609.6 -5.1997230557,49.9759171581,609.6 -5.1957280378,49.9781793605,609.6 -5.1921145031,49.9806943547,609.6 -5.1889207647,49.9834355182,609.6 -5.1861807094,49.9863738295,609.6 -5.1839234367,49.98947817460001,609.6 -5.1821729487,49.9927156753,609.6 -5.1809478918,49.9960520364,609.6 -5.1802613559,49.99945190819999,609.6 -5.1801207307,50.0028792609,609.6 -5.180527623,50.0062977655,609.6 -5.1814778347,50.0096711794,609.6 -5.1829614021,50.0129637305,609.6 -5.1849626974,50.0161404971,609.6 -5.1874605898,50.0191677788,609.6 -5.1904286663,50.0220134548,609.6 -5.1938355086,50.0246473257,609.6 -5.1976450242,50.0270414353,609.6 -5.2018168287,50.0291703683,609.6 -5.2063066733,50.0310115211,609.6 -5.2110669151,50.0325453435,609.6 -5.2160470246,50.0337555467,609.6 -5.221194124,50.03462927759999,609.6 -5.2264535514,50.0351572562,609.6 -5.2317694444,50.0353338744,609.6 + + + + +
+ + EGRU004B PREDANNACK RWY 05 + 495742N 0051701W -
495805N 0051736W -
495854N 0051622W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495831N 0051546W -
495742N 0051701W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2835419444,49.9617730833,609.6 -5.2627449167,49.97538555559999,609.6 -5.2663444516,49.9772937977,609.6 -5.2696628728,49.979403434,609.6 -5.2726731667,49.9816973056,609.6 -5.2934640556,49.9680870278,609.6 -5.2835419444,49.9617730833,609.6 + + + + +
+ + EGRU004C PREDANNACK RWY 23 + 500232N 0051048W -
500209N 0051012W -
500121N 0051127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500143N 0051203W -
500232N 0051048W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1799270833,50.04227241670001,609.6 -5.2007712222,50.0286782778,609.6 -5.1971696359,50.0267686512,609.6 -5.1938502156,50.024657554,609.6 -5.19084,50.0223621944,609.6 -5.1699896944,50.03595852779999,609.6 -5.1799270833,50.04227241670001,609.6 + + + + +
+ + EGRU004D PREDANNACK RWY 09 + 495940N 0051842W -
500013N 0051843W -
500013N 0051700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495940N 0051656W -
495940N 0051842W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3117936944,49.9944973611,609.6 -5.2821116389,49.9945571944,609.6 -5.2829561989,49.9975243578,609.6 -5.2833808119,50.0005286115,609.6 -5.2833819167,50.0035453056,609.6 -5.3118256944,50.0034878056,609.6 -5.3117936944,49.9944973611,609.6 + + + + +
+ + EGRU004E PREDANNACK RWY 27 + 500013N 0050926W -
495941N 0050926W -
495941N 0051053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500013N 0051049W -
500013N 0050926W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1573170556,50.00371624999999,609.6 -5.180168,50.0036954167,609.6 -5.1801480057,50.00067875660001,609.6 -5.1805515819,49.9976733054,609.6 -5.1813753611,49.99470372219999,609.6 -5.1572850556,49.99472580559999,609.6 -5.1573170556,50.00371624999999,609.6 + + + + +
+ + EGRU004F PREDANNACK RWY 13 + 500131N 0051744W -
500157N 0051713W -
500127N 0051613W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500100N 0051641W -
500131N 0051744W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2954350278,50.0253619444,609.6 -5.2780854722,50.0167982778,609.6 -5.2758280709,50.0194338016,609.6 -5.2732102702,50.02192715809999,609.6 -5.2702534167,50.0242579444,609.6 -5.2869394444,50.0324947222,609.6 -5.2954350278,50.0253619444,609.6 + + + + +
+ + EGRU004G PREDANNACK RWY 31 + 495826N 0051006W -
495800N 0051037W -
495837N 0051152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495902N 0051119W -
495826N 0051006W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1683617778,49.97384749999999,609.6 -5.1885124444,49.9838324444,609.6 -5.1912391424,49.9813889971,609.6 -5.1942966282,49.9791142377,609.6 -5.1976598889,49.9770267222,609.6 -5.1768470278,49.9667146667,609.6 -5.1683617778,49.97384749999999,609.6 + + + + +
+ + EGRU004H PREDANNACK RWY 18 + 500307N 0051420W -
500308N 0051330W -
500206N 0051328W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500206N 0051419W -
500307N 0051420W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2389025278,50.05208019439999,609.6 -5.2384789167,50.0350520833,609.6 -5.2338293861,50.035307421,609.6 -5.2291630406,50.0352915093,609.6 -5.2245179722,50.0350044722,609.6 -5.2249413611,50.0522232222,609.6 -5.2389025278,50.05208019439999,609.6 + + + + +
+ + EGRU004I PREDANNACK RWY 36 + 495707N 0051321W -
495706N 0051411W -
495808N 0051413W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495809N 0051322W -
495707N 0051321W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2224781111,49.9518661389,609.6 -5.2229034722,49.9692269444,609.6 -5.2275257288,49.9688452124,609.6 -5.2321824878,49.9687336718,609.6 -5.2368358889,49.96889322219999,609.6 -5.23641025,49.9517231111,609.6 -5.2224781111,49.9518661389,609.6 + + + + +
+ + EGRU005A NEWQUAY + A circle, 2.5 NM radius, centred at 502627N 0045943W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.995375,50.4823974866,609.6 -5.0013939644,50.4822197775,609.6 -5.0073614427,50.4816881703,609.6 -5.0132263927,50.4808072122,609.6 -5.0189386559,50.4795844382,609.6 -5.0244493897,50.47803030640001,609.6 -5.0297114877,50.47615810770001,609.6 -5.0346799846,50.4739838514,609.6 -5.0393124424,50.47152612730001,609.6 -5.0435693141,50.4688059458,609.6 -5.0474142818,50.4658465572,609.6 -5.0508145666,50.462673252,609.6 -5.0537412075,50.4593131434,609.6 -5.0561693067,50.4557949349,609.6 -5.0580782394,50.4521486742,609.6 -5.0594518272,50.44840549540001,609.6 -5.0602784716,50.4445973531,609.6 -5.0605512498,50.4407567484,609.6 -5.0602679685,50.4369164519,609.6 -5.0594311786,50.43310922370001,609.6 -5.0580481486,50.4293675339,609.6 -5.0561307983,50.4257232862,609.6 -5.0536955929,50.4222075464,609.6 -5.0507633991,50.4188502779,609.6 -5.0473593039,50.4156800876,609.6 -5.043512398,50.41272398260001,609.6 -5.0392555263,50.4100071416,609.6 -5.0346250067,50.40755270109999,609.6 -5.0296603202,50.40538155969999,609.6 -5.024403775,50.4035122011,609.6 -5.0189001474,50.401960538,609.6 -5.0131963018,50.4007397771,609.6 -5.0073407941,50.3998603079,609.6 -5.0013834612,50.39932961489999,609.6 -4.995375,50.39915221399999,609.6 -4.9893665388,50.39932961489999,609.6 -4.9834092059,50.3998603079,609.6 -4.9775536982,50.4007397771,609.6 -4.9718498526,50.401960538,609.6 -4.966346225,50.4035122011,609.6 -4.9610896798,50.40538155969999,609.6 -4.9561249933,50.40755270109999,609.6 -4.9514944737,50.4100071416,609.6 -4.947237602,50.41272398260001,609.6 -4.9433906961,50.4156800876,609.6 -4.9399866009,50.4188502779,609.6 -4.9370544071,50.4222075464,609.6 -4.9346192017,50.4257232862,609.6 -4.9327018514,50.4293675339,609.6 -4.9313188214,50.43310922370001,609.6 -4.9304820315,50.4369164519,609.6 -4.9301987502,50.4407567484,609.6 -4.9304715284,50.4445973531,609.6 -4.9312981728,50.44840549540001,609.6 -4.9326717606,50.4521486742,609.6 -4.9345806933,50.4557949349,609.6 -4.9370087925,50.4593131434,609.6 -4.9399354334,50.462673252,609.6 -4.9433357182,50.4658465572,609.6 -4.9471806859,50.4688059458,609.6 -4.9514375576,50.47152612730001,609.6 -4.9560700154,50.4739838514,609.6 -4.9610385123,50.47615810770001,609.6 -4.9663006103,50.47803030640001,609.6 -4.9718113441,50.4795844382,609.6 -4.9775236073,50.4808072122,609.6 -4.9833885573,50.4816881703,609.6 -4.9893560356,50.4822197775,609.6 -4.995375,50.4823974866,609.6 + + + + +
+ + EGRU005B NEWQUAY RWY 12 + 502758N 0050435W -
502825N 0050409W -
502756N 0050252W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to
502728N 0050317W -
502758N 0050435W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0762666667,50.46597222219999,609.6 -5.0547863333,50.4579050556,609.6 -5.0526992207,50.4605952669,609.6 -5.0503135172,50.4631823971,609.6 -5.0476416111,50.4656529722,609.6 -5.0691111111,50.4737166667,609.6 -5.0762666667,50.46597222219999,609.6 + + + + +
+ + EGRU005C NEWQUAY RWY 30 + 502501N 0045506W -
502433N 0045531W -
502457N 0045635W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to
502525N 0045610W -
502501N 0045506W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9182166667,50.4169,609.6 -4.9360059167,50.4236155278,609.6 -4.9380977536,50.4209275579,609.6 -4.9404871378,50.41834285089999,609.6 -4.9431616111,50.4158748333,609.6 -4.9253611111,50.4091555556,609.6 -4.9182166667,50.4169,609.6 + + + + +
+ + EGRU006A EXETER + A circle, 2.5 NM radius, centred at 504403N 0032450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4138111111,50.7759120447,609.6 -3.4198676675,50.775734343,609.6 -3.4258724149,50.77520275789999,609.6 -3.4317739908,50.7743218365,609.6 -3.4375219223,50.7730991138,609.6 -3.4430670607,50.7715450477,609.6 -3.4483620045,50.7696729288,609.6 -3.4533615069,50.7674987661,609.6 -3.4580228647,50.76504114909999,609.6 -3.4623062837,50.7623210878,609.6 -3.4661752198,50.7593618318,609.6 -3.4695966899,50.7561886708,609.6 -3.4725415531,50.75282871739999,609.6 -3.4749847572,50.7493106742,609.6 -3.4769055504,50.7456645876,609.6 -3.4782876544,50.74192159060001,609.6 -3.4791194006,50.7381136364,609.6 -3.4793938246,50.7342732247,609.6 -3.479108721299999,50.7304331244,609.6 -3.4782666594,50.726626094,609.6 -3.4768749545,50.72288460170001,609.6 -3.4749456026,50.7192405493,609.6 -3.4724951729,50.7157250007,609.6 -3.4695446637,50.71236791740001,609.6 -3.4661193192,50.7091979042,609.6 -3.4622484124,50.7062419664,609.6 -3.4579649933,50.7035252806,609.6 -3.4533056062,50.70107098179999,609.6 -3.448309978200001,50.6988999669,609.6 -3.4430206805,50.6970307181,609.6 -3.4374827676,50.69547914659999,609.6 -3.4317433949,50.6942584582,609.6 -3.425851419799999,50.6933790415,609.6 -3.4198569881,50.6928483801,609.6 -3.4138111111,50.6926709899,609.6 -3.407765234100001,50.6928483801,609.6 -3.4017708025,50.6933790415,609.6 -3.3958788273,50.6942584582,609.6 -3.3901394546,50.69547914659999,609.6 -3.3846015417,50.6970307181,609.6 -3.379312244,50.6988999669,609.6 -3.374316616,50.70107098179999,609.6 -3.3696572289,50.7035252806,609.6 -3.3653738098,50.7062419664,609.6 -3.361502903,50.7091979042,609.6 -3.358077558499999,50.71236791740001,609.6 -3.3551270493,50.7157250007,609.6 -3.3526766197,50.7192405493,609.6 -3.3507472677,50.72288460170001,609.6 -3.3493555629,50.726626094,609.6 -3.348513501,50.7304331244,609.6 -3.3482283977,50.7342732247,609.6 -3.3485028216,50.7381136364,609.6 -3.3493345678,50.74192159060001,609.6 -3.3507166719,50.7456645876,609.6 -3.352637465,50.7493106742,609.6 -3.3550806691,50.75282871739999,609.6 -3.3580255323,50.7561886708,609.6 -3.3614470024,50.7593618318,609.6 -3.365315938500001,50.7623210878,609.6 -3.3695993576,50.76504114909999,609.6 -3.3742607153,50.7674987661,609.6 -3.3792602178,50.7696729288,609.6 -3.3845551615,50.7715450477,609.6 -3.3901002999,50.7730991138,609.6 -3.3958482314,50.7743218365,609.6 -3.4017498073,50.77520275789999,609.6 -3.4077545547,50.775734343,609.6 -3.4138111111,50.7759120447,609.6 + + + + +
+ + EGRU006B EXETER RWY 08 + 504301N 0032942W -
504332N 0032954W -
504343N 0032844W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to
504312N 0032831W -
504301N 0032942W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.495058333299999,50.7169166667,609.6 -3.4754004444,50.7200062778,609.6 -3.476864009799999,50.7228603054,609.6 -3.4779999174,50.72577385219999,609.6 -3.4788021944,50.7287317778,609.6 -3.4984444444,50.7256444444,609.6 -3.495058333299999,50.7169166667,609.6 + + + + +
+ + EGRU006C EXETER RWY 26 + 504506N 0031958W -
504434N 0031946W -
504423N 0032056W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to
504455N 0032108W -
504506N 0031958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3329055556,50.7515472222,609.6 -3.3521841667,50.7485441667,609.6 -3.3507272916,50.7456883341,609.6 -3.3495987816,50.7427732951,609.6 -3.3488044444,50.7398142222,609.6 -3.3295111111,50.74281944440001,609.6 -3.3329055556,50.7515472222,609.6 + + + + +
+ + EGRU007A DUNKESWELL + A circle, 2 NM radius, centred at 505136N 0031405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.234722222199999,50.8932956049,609.6 -3.2401351738,50.8931190092,609.6 -3.2454906252,50.8925910977,609.6 -3.2507316905,50.89171747819999,609.6 -3.2558027069,50.8905074303,609.6 -3.260649828400001,50.888973806,609.6 -3.2652216011,50.8871328929,609.6 -3.269469511400001,50.8850042399,609.6 -3.2733485023,50.88261044859999,609.6 -3.2768174528,50.8799769321,609.6 -3.279839613,50.877131644,609.6 -3.2823829938,50.8741047808,609.6 -3.284420702899999,50.8709284596,609.6 -3.2859312278,50.8676363769,609.6 -3.2868986599,50.8642634502,609.6 -3.2873128583,50.8608454468,609.6 -3.2871695533,50.85741860420001,609.6 -3.2864703856,50.8540192458,609.6 -3.2852228848,50.8506833957,609.6 -3.2834403834,50.8474463977,609.6 -3.2811418721,50.8443425409,609.6 -3.2783517935,50.84140469750001,609.6 -3.275099780300001,50.8386639756,609.6 -3.2714203384,50.8361493907,609.6 -3.2673524801,50.8338875599,609.6 -3.2629393099,50.8319024213,609.6 -3.2582275683,50.83021498160001,609.6 -3.253267138,50.8288430954,609.6 -3.2481105182,50.82780127699999,609.6 -3.2428122708,50.8271005476,609.6 -3.237428447,50.82674832000001,609.6 -3.2320159975,50.82674832000001,609.6 -3.2266321737,50.8271005476,609.6 -3.2213339263,50.82780127699999,609.6 -3.2161773064,50.8288430954,609.6 -3.2112168762,50.83021498160001,609.6 -3.2065051345,50.8319024213,609.6 -3.2020919643,50.8338875599,609.6 -3.198024106,50.8361493907,609.6 -3.1943446642,50.8386639756,609.6 -3.1910926509,50.84140469750001,609.6 -3.1883025723,50.8443425409,609.6 -3.186004061,50.8474463977,609.6 -3.1842215597,50.8506833957,609.6 -3.182974058800001,50.8540192458,609.6 -3.1822748912,50.85741860420001,609.6 -3.1821315861,50.8608454468,609.6 -3.1825457846,50.8642634502,609.6 -3.1835132166,50.8676363769,609.6 -3.185023741599999,50.8709284596,609.6 -3.1870614507,50.8741047808,609.6 -3.1896048314,50.877131644,609.6 -3.192626991700001,50.8799769321,609.6 -3.196095942099999,50.88261044859999,609.6 -3.1999749331,50.8850042399,609.6 -3.2042228433,50.8871328929,609.6 -3.208794616,50.888973806,609.6 -3.2136417376,50.8905074303,609.6 -3.2187127539,50.89171747819999,609.6 -3.2239538193,50.8925910977,609.6 -3.2293092706,50.8931190092,609.6 -3.234722222199999,50.8932956049,609.6 + + + + +
+ + EGRU007B DUNKESWELL RWY 04 + 504912N 0031650W -
504933N 0031729W -
505017N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to
504956N 0031549W -
504912N 0031650W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.280597222199999,50.81986666669999,609.6 -3.2636403056,50.8321895278,609.6 -3.2674813106,50.8339522696,609.6 -3.2710560959,50.8359269644,609.6 -3.2743355833,50.83809755560001,609.6 -3.2912888889,50.82577499999999,609.6 -3.280597222199999,50.81986666669999,609.6 + + + + +
+ + EGRU007C DUNKESWELL RWY 22 + 505400N 0031120W -
505339N 0031042W -
505255N 0031142W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to
505316N 0031221W -
505400N 0031120W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1889333333,50.9000361111,609.6 -3.2058049722,50.88781786109999,609.6 -3.2019593037,50.88605486699999,609.6 -3.198380808500001,50.88407967649999,609.6 -3.195098638899999,50.8819083889,609.6 -3.178222222200001,50.8941277778,609.6 -3.1889333333,50.9000361111,609.6 + + + + +
+ + EGRU008A MERRYFIELD + A circle, 2.5 NM radius, centred at 505747N 0025620W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9388138889,51.0047548483,609.6 -2.944900194300001,51.0045771522,609.6 -2.950934435,51.0040455843,609.6 -2.9568649954,51.00316469140001,609.6 -2.9626411535,51.0019420085,609.6 -2.9682135183,51.00038799330001,609.6 -2.9735344549,50.9985159364,609.6 -2.9785584938,50.9963418465,609.6 -2.9832427217,50.9938843127,609.6 -2.987547149300001,50.9911643446,609.6 -2.9914350528,50.9882051916,609.6 -2.9948732879,50.9850321428,609.6 -2.9978325712,50.98167231010001,609.6 -3.0002877285,50.9781543952,609.6 -3.0022179071,50.974508444,609.6 -3.0036067504,50.9707655884,609.6 -3.0044425336,50.9669577805,609.6 -3.0047182595,50.963117519,609.6 -3.004431714,50.9592775715,609.6 -3.0035854798,50.955470695,609.6 -3.0021869098,50.9517293565,609.6 -3.000248060000001,50.94808545630001,609.6 -2.997785582400001,50.94457005659999,609.6 -2.9948205789,50.9412131175,609.6 -2.9913784186,50.93804324229999,609.6 -2.9874885185,50.9350874347,609.6 -2.983184091,50.93237087,609.6 -2.9785018596,50.9299166817,609.6 -2.9734817459,50.9277457654,609.6 -2.9681665295,50.9258766021,609.6 -2.9626014849,50.9243251021,609.6 -2.956833998,50.9231044702,609.6 -2.9509131644,50.9222250943,609.6 -2.944889374799999,50.9216944577,609.6 -2.9388138889,50.9215170757,609.6 -2.932738403,50.9216944577,609.6 -2.9267146134,50.9222250943,609.6 -2.9207937798,50.9231044702,609.6 -2.9150262928,50.9243251021,609.6 -2.9094612483,50.9258766021,609.6 -2.9041460319,50.9277457654,609.6 -2.8991259182,50.9299166817,609.6 -2.8944436868,50.93237087,609.6 -2.8901392593,50.9350874347,609.6 -2.8862493592,50.93804324229999,609.6 -2.8828071989,50.9412131175,609.6 -2.8798421954,50.94457005659999,609.6 -2.8773797178,50.94808545630001,609.6 -2.875440868,50.9517293565,609.6 -2.874042298,50.955470695,609.6 -2.8731960637,50.9592775715,609.6 -2.872909518200001,50.963117519,609.6 -2.8731852442,50.9669577805,609.6 -2.8740210274,50.9707655884,609.6 -2.8754098707,50.974508444,609.6 -2.8773400493,50.9781543952,609.6 -2.8797952066,50.98167231010001,609.6 -2.8827544899,50.9850321428,609.6 -2.886192725,50.9882051916,609.6 -2.8900806285,50.9911643446,609.6 -2.894385056,50.9938843127,609.6 -2.899069284,50.9963418465,609.6 -2.9040933229,50.9985159364,609.6 -2.9094142595,51.00038799330001,609.6 -2.9149866243,51.0019420085,609.6 -2.9207627824,51.00316469140001,609.6 -2.9266933427,51.0040455843,609.6 -2.9327275835,51.0045771522,609.6 -2.9388138889,51.0047548483,609.6 + + + + +
+ + EGRU008B MERRYFIELD RWY 03 + 505506N 0025754W -
505519N 0025840W -
505540N 0025825W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505526N 0025739W -
505506N 0025754W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9648844444,50.9183033056,609.6 -2.9608878056,50.9239230833,609.6 -2.9653039687,50.9250301094,609.6 -2.9695825808,50.9263353435,609.6 -2.9737014167,50.927832,609.6 -2.9778534167,50.9219914444,609.6 -2.9648844444,50.9183033056,609.6 + + + + +
+ + EGRU008C MERRYFIELD RWY 21 + 510051N 0025444W -
510038N 0025357W -
505958N 0025425W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
510011N 0025512W -
510051N 0025444W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.912232250000001,51.0141108611,609.6 -2.92012775,51.0030484167,609.6 -2.915615938799999,51.0020936564,609.6 -2.911225174100001,51.00093597,609.6 -2.9069783611,50.9995813889,609.6 -2.8992376111,51.0104227778,609.6 -2.912232250000001,51.0141108611,609.6 + + + + +
+ + EGRU008D MERRYFIELD RWY 09 + 505714N 0030118W -
505746N 0030122W -
505750N 0030017W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505718N 0030012W -
505714N 0030118W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0216006389,50.9538749444,609.6 -3.0034171389,50.95492480559999,609.6 -3.004188227499999,50.9578865645,609.6 -3.0046194034,50.9608757179,609.6 -3.0047083611,50.96387672219999,609.6 -3.0228821389,50.9628273889,609.6 -3.0216006389,50.9538749444,609.6 + + + + +
+ + EGRU008E MERRYFIELD RWY 27 + 505820N 0025122W -
505748N 0025117W -
505745N 0025223W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505817N 0025227W -
505820N 0025122W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8560128611,50.9723541944,609.6 -2.8741930833,50.971328,609.6 -2.8734281588,50.9683656014,609.6 -2.8730034372,50.9653760928,609.6 -2.8729210556,50.96237502780001,609.6 -2.8547311111,50.96340175,609.6 -2.8560128611,50.9723541944,609.6 + + + + +
+ + EGRU008F MERRYFIELD RWY 16 + 510036N 0025807W -
510047N 0025718W -
510015N 0025702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
510006N 0025751W -
510036N 0025807W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9685856389,51.01010763890001,609.6 -2.9641047222,51.0015711389,609.6 -2.9596462924,51.0026227467,609.6 -2.9550791053,51.0034685703,609.6 -2.950427,51.0041041944,609.6 -2.9550573333,51.01293025,609.6 -2.9685856389,51.01010763890001,609.6 + + + + +
+ + EGRU008G MERRYFIELD RWY 34 + 505508N 0025421W -
505458N 0025510W -
505522N 0025522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505533N 0025434W -
505508N 0025421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9058088333,50.9188734444,609.6 -2.9094674444,50.9258746667,609.6 -2.913795743000001,50.9246351369,609.6 -2.9182540045,50.9235959522,609.6 -2.922819055600001,50.9227625,609.6 -2.9193098333,50.9160507778,609.6 -2.9058088333,50.9188734444,609.6 + + + + +
+ + EGRU009A YEOVIL/WESTLAND + 505817N 0024035W -
505804N 0023747W thence clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to -
505817N 0024035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6762913333,50.97146936109999,609.6 -2.6813214099,50.9701675861,609.6 -2.6861121821,50.9685455593,609.6 -2.6906126594,50.9666205383,609.6 -2.6947749661,50.9644130177,609.6 -2.6985548452,50.9619464963,609.6 -2.7019121291,50.9592472264,609.6 -2.7048111668,50.9563439325,609.6 -2.7072212013,50.9532675051,609.6 -2.7091166941,50.9500506702,609.6 -2.7104775937,50.9467276407,609.6 -2.7112895447,50.9433337517,609.6 -2.7115440354,50.93990508379999,609.6 -2.7112384838,50.93647807970001,609.6 -2.7103762595,50.9330891564,609.6 -2.7089666428,50.9297743184,609.6 -2.7070247211,50.9265687754,609.6 -2.7045712243,50.9235065695,609.6 -2.7016323001,50.9206202139,609.6 -2.6982392335,50.917940349,609.6 -2.694428112,50.91549541799999,609.6 -2.690239441,50.9133113666,609.6 -2.685717713,50.9114113683,609.6 -2.6809109363,50.90981558049999,609.6 -2.6758701262,50.908540931,609.6 -2.6706487661,50.9076009399,609.6 -2.6653022429,50.9070055769,609.6 -2.6598872626,50.9067611562,609.6 -2.6544612525,50.90687027,609.6 -2.6490817564,50.907331761,609.6 -2.6438058276,50.908140735,609.6 -2.6386894283,50.9092886121,609.6 -2.6337868387,50.91076321700001,609.6 -2.6291500848,50.91254890809999,609.6 -2.6248283884,50.91462674169999,609.6 -2.6208676465,50.9169746722,609.6 -2.6173099448,50.9195677849,609.6 -2.614193111,50.922378559,609.6 -2.6115503118,50.9253771585,609.6 -2.6094096989,50.928531748,609.6 -2.6077941069,50.9318088292,609.6 -2.6067208071,50.9351735959,609.6 -2.6062013196,50.93859030339999,609.6 -2.6062412861,50.9420226471,609.6 -2.6068404051,50.9454341484,609.6 -2.6079924294,50.9487885423,609.6 -2.6096852278,50.9520501632,609.6 -2.6119009088,50.95518432450001,609.6 -2.6146160072,50.9581576886,609.6 -2.6178017294,50.9609386219,609.6 -2.6214242569,50.96349753249999,609.6 -2.6254451044,50.9658071869,609.6 -2.6298215278,50.96784299999999,609.6 -2.6762913333,50.97146936109999,609.6 + + + + +
+ + EGRU009B YEOVIL/WESTLAND RWY 09 + 505614N 0024415W -
505646N 0024414W -
505644N 0024239W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to
505612N 0024241W -
505614N 0024415W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7375611111,50.93712777779999,609.6 -2.7112603056,50.9366077222,609.6 -2.7115396944,50.9396068368,609.6 -2.7113901,50.9426096531,609.6 -2.7108126389,50.9455917222,609.6 -2.7371027778,50.9461111111,609.6 -2.7375611111,50.93712777779999,609.6 + + + + +
+ + EGRU009C YEOVIL/WESTLAND RWY 27 + 505635N 0023449W -
505602N 0023450W -
505604N 0023625W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to
505636N 0023623W -
505635N 0023449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5801416667,50.9429222222,609.6 -2.6064268056,50.9434709722,609.6 -2.6061537863,50.9404710151,609.6 -2.6063099945,50.9374677222,609.6 -2.6068940556,50.93448555560001,609.6 -2.5805972222,50.9339361111,609.6 -2.5801416667,50.9429222222,609.6 + + + + +
+ + EGRU010A COMPTON ABBAS + A circle, 2 NM radius, centred at 505802N 0020913W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1536111111,51.0005172124,609.6 -2.1590365291,51.00034061940001,609.6 -2.1644043138,50.9998127162,609.6 -2.1696574483,50.9989391106,609.6 -2.1747401408,50.9977290819,609.6 -2.1795984212,50.9961954822,609.6 -2.1841807168,50.9943545989,609.6 -2.1884384021,50.9922259806,609.6 -2.1923263164,50.9898322288,609.6 -2.1958032439,50.98719875640001,609.6 -2.1988323506,50.98435351660001,609.6 -2.2013815737,50.9813267053,609.6 -2.2034239597,50.9781504395,609.6 -2.2049379469,50.9748584151,609.6 -2.2059075905,50.9714855491,609.6 -2.2063227271,50.9680676081,609.6 -2.2061790777,50.964640829,609.6 -2.2054782875,50.96124153460001,609.6 -2.2042279037,50.9579057482,609.6 -2.2024412905,50.9546688129,609.6 -2.2001374823,50.95156501700001,609.6 -2.1973409787,50.948627232,609.6 -2.1940814806,50.9458865651,609.6 -2.1903935737,50.9433720314,609.6 -2.1863163598,50.941110247,609.6 -2.1818930427,50.9391251494,609.6 -2.1771704701,50.9374377449,609.6 -2.1721986392,50.9360658874,609.6 -2.1670301693,50.9350240909,609.6 -2.1617197477,50.9343233764,609.6 -2.1563235537,50.93397115619999,609.6 -2.1508986685,50.93397115619999,609.6 -2.1455024745,50.9343233764,609.6 -2.1401920529,50.9350240909,609.6 -2.135023583,50.9360658874,609.6 -2.1300517522,50.9374377449,609.6 -2.1253291795,50.9391251494,609.6 -2.1209058624,50.941110247,609.6 -2.1168286486,50.9433720314,609.6 -2.1131407416,50.9458865651,609.6 -2.1098812435,50.948627232,609.6 -2.1070847399,50.95156501700001,609.6 -2.1047809318,50.9546688129,609.6 -2.1029943185,50.9579057482,609.6 -2.1017439347,50.96124153460001,609.6 -2.1010431445,50.964640829,609.6 -2.1008994951,50.9680676081,609.6 -2.1013146317,50.9714855491,609.6 -2.1022842754,50.9748584151,609.6 -2.1037982626,50.9781504395,609.6 -2.1058406485,50.9813267053,609.6 -2.1083898716,50.98435351660001,609.6 -2.1114189783,50.98719875640001,609.6 -2.1148959058,50.9898322288,609.6 -2.1187838201,50.9922259806,609.6 -2.1230415054,50.9943545989,609.6 -2.127623801,50.9961954822,609.6 -2.1324820814,50.9977290819,609.6 -2.137564774,50.9989391106,609.6 -2.1428179084,50.9998127162,609.6 -2.1481856932,51.00034061940001,609.6 -2.1536111111,51.0005172124,609.6 + + + + +
+ + EGRU010B COMPTON ABBAS RWY 08 + 505708N 0021337W -
505739N 0021349W -
505752N 0021222W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to
505720N 0021211W -
505708N 0021337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2270083333,50.9520972222,609.6 -2.2029971944,50.9555675556,609.6 -2.2044610998,50.9584260794,609.6 -2.2055112153,50.9613562969,609.6 -2.2061389167,50.9643343611,609.6 -2.2301694444,50.9608611111,609.6 -2.2270083333,50.9520972222,609.6 + + + + +
+ + EGRU010C COMPTON ABBAS RWY 26 + 505857N 0020449W -
505825N 0020438W -
505813N 0020604W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to
505844N 0020615W -
505857N 0020449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0802805556,50.9824361111,609.6 -2.1042831944,50.97899544440001,609.6 -2.1028044889,50.9761396879,609.6 -2.1017397236,50.9732113938,609.6 -2.1010975,50.9702344167,609.6 -2.0771138889,50.97367222220001,609.6 -2.0802805556,50.9824361111,609.6 + + + + +
+ + EGRU011A BOURNEMOUTH + A circle, 2.5 NM radius, centred at 504648N 0015033W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8425138889,50.8216839385,609.6 -1.8485763644,50.8215062379,609.6 -1.8545869801,50.82097465619999,609.6 -1.860494323,50.8200937406,609.6 -1.8662478708,50.8188710258,609.6 -1.8717984264,50.8173169699,609.6 -1.8770985419,50.81544486349999,609.6 -1.8821029264,50.8132707154,609.6 -1.8867688346,50.810813115,609.6 -1.8910564338,50.8080930724,609.6 -1.8949291438,50.805133837,609.6 -1.8983539496,50.8019606985,609.6 -1.901301682,50.7986007693,609.6 -1.9037472645,50.79508275180001,609.6 -1.9056699251,50.7914366922,609.6 -1.9070533701,50.7876937236,609.6 -1.9078859195,50.7838857986,609.6 -1.9081606025,50.780045417,609.6 -1.9078752123,50.77620534730001,609.6 -1.9070323202,50.7723983477,609.6 -1.9056392495,50.76865688609999,609.6 -1.9037080077,50.7650128642,609.6 -1.9012551809,50.7614973454,609.6 -1.8983017878,50.758140291,609.6 -1.8948730975,50.75497030530001,609.6 -1.8909984115,50.75201439360001,609.6 -1.8867108124,50.7492977321,609.6 -1.88204688,50.7468434554,609.6 -1.87704638,50.74467246020001,609.6 -1.8717519253,50.7428032284,609.6 -1.866208614,50.7412516713,609.6 -1.8604636474,50.7400309942,609.6 -1.8545659302,50.7391515856,609.6 -1.8485656572,50.73862092920001,609.6 -1.8425138889,50.7384435406,609.6 -1.8364621206,50.73862092920001,609.6 -1.8304618475,50.7391515856,609.6 -1.8245641304,50.7400309942,609.6 -1.8188191638,50.7412516713,609.6 -1.8132758525,50.7428032284,609.6 -1.8079813978,50.74467246020001,609.6 -1.8029808978,50.7468434554,609.6 -1.7983169654,50.7492977321,609.6 -1.7940293662,50.75201439360001,609.6 -1.7901546803,50.75497030530001,609.6 -1.78672599,50.758140291,609.6 -1.7837725969,50.7614973454,609.6 -1.78131977,50.7650128642,609.6 -1.7793885283,50.76865688609999,609.6 -1.7779954575,50.7723983477,609.6 -1.7771525655,50.77620534730001,609.6 -1.7768671752,50.780045417,609.6 -1.7771418583,50.7838857986,609.6 -1.7779744077,50.7876937236,609.6 -1.7793578527,50.7914366922,609.6 -1.7812805133,50.79508275180001,609.6 -1.7837260958,50.7986007693,609.6 -1.7866738282,50.8019606985,609.6 -1.790098634,50.805133837,609.6 -1.793971344,50.8080930724,609.6 -1.7982589432,50.810813115,609.6 -1.8029248514,50.8132707154,609.6 -1.8079292359,50.81544486349999,609.6 -1.8132293514,50.8173169699,609.6 -1.818779907,50.8188710258,609.6 -1.8245334547,50.8200937406,609.6 -1.8304407977,50.82097465619999,609.6 -1.8364514133,50.8215062379,609.6 -1.8425138889,50.8216839385,609.6 + + + + +
+ + EGRU011B BOURNEMOUTH RWY 08 + 504546N 0015508W -
504617N 0015521W -
504626N 0015427W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to
504555N 0015414W -
504546N 0015508W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9189138889,50.7626972222,609.6 -1.9038303611,50.7652141944,609.6 -1.9053602225,50.768054234,609.6 -1.906563561,50.7709567886,609.6 -1.9074340556,50.7739067778,609.6 -1.9225055556,50.7713916667,609.6 -1.9189138889,50.7626972222,609.6 + + + + +
+ + EGRU011C BOURNEMOUTH RWY 26 + 504754N 0014536W -
504723N 0014523W -
504710N 0014639W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to
504742N 0014652W -
504754N 0014536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7601111111,50.798375,609.6 -1.7811646111,50.79489127780001,609.6 -1.7796401409,50.7920496202,609.6 -1.7784428843,50.7891457046,609.6 -1.7775790278,50.7861946389,609.6 -1.7565111111,50.7896805556,609.6 -1.7601111111,50.798375,609.6 + + + + +
+ + EGRU012A SOUTHAMPTON + A circle, 2 NM radius, centred at 505701N 0012124W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3566666667,50.9835728651,609.6 -1.3620901095,50.9833962716,609.6 -1.3674559401,50.9828683672,609.6 -1.3727071623,50.98199475929999,609.6 -1.3777880049,50.98078472760001,609.6 -1.3826445173,50.97925112400001,609.6 -1.3872251457,50.977410236,609.6 -1.3914812822,50.97528161220001,609.6 -1.3953677827,50.9728878542,609.6 -1.3988434463,50.97025437479999,609.6 -1.4018714524,50.9674091274,609.6 -1.4044197499,50.9643823079,609.6 -1.4064613948,50.9612060334,609.6 -1.4079748335,50.9579139998,609.6 -1.4089441267,50.9545411242,609.6 -1.4093591147,50.9511231733,609.6 -1.4092155198,50.94769638419999,609.6 -1.4085149867,50.9442970796,609.6 -1.4072650597,50.9409612832,609.6 -1.4054790979,50.937724338,609.6 -1.403176129,50.9346205324,609.6 -1.4003806434,50.9316827382,609.6 -1.3971223312,50.9289420627,609.6 -1.3934357654,50.9264275208,609.6 -1.3893600339,50.9241657291,609.6 -1.3849383244,50.9221806251,609.6 -1.3802174678,50.92049321499999,609.6 -1.3752474433,50.91912135299999,609.6 -1.3700808509,50.918079553,609.6 -1.3647723582,50.91737883609999,609.6 -1.3593781241,50.9170266148,609.6 -1.3539552092,50.9170266148,609.6 -1.3485609751,50.91737883609999,609.6 -1.3432524824,50.918079553,609.6 -1.3380858901,50.91912135299999,609.6 -1.3331158655,50.92049321499999,609.6 -1.3283950089,50.9221806251,609.6 -1.3239732994,50.9241657291,609.6 -1.3198975679,50.9264275208,609.6 -1.3162110021,50.9289420627,609.6 -1.31295269,50.9316827382,609.6 -1.3101572043,50.9346205324,609.6 -1.3078542354,50.937724338,609.6 -1.3060682736,50.9409612832,609.6 -1.3048183467,50.9442970796,609.6 -1.3041178135,50.94769638419999,609.6 -1.3039742186,50.9511231733,609.6 -1.3043892067,50.9545411242,609.6 -1.3053584999,50.9579139998,609.6 -1.3068719385,50.9612060334,609.6 -1.3089135835,50.9643823079,609.6 -1.3114618809,50.9674091274,609.6 -1.314489887,50.97025437479999,609.6 -1.3179655506,50.9728878542,609.6 -1.3218520511,50.97528161220001,609.6 -1.3261081877,50.977410236,609.6 -1.330688816,50.97925112400001,609.6 -1.3355453284,50.98078472760001,609.6 -1.340626171,50.98199475929999,609.6 -1.3458773932,50.9828683672,609.6 -1.3512432239,50.9833962716,609.6 -1.3566666667,50.9835728651,609.6 + + + + +
+ + EGRU012B SOUTHAMPTON RWY 02 + 505359N 0012239W -
505410N 0012327W -
505514N 0012251W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to
505504N 0012203W -
505359N 0012239W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3774111111,50.8996805556,609.6 -1.3674003333,50.9176806667,609.6 -1.3720051772,50.9184244585,609.6 -1.3764853887,50.9194274358,609.6 -1.3808045556,50.9206814444,609.6 -1.3908194444,50.9026638889,609.6 -1.3774111111,50.8996805556,609.6 + + + + +
+ + EGRU012C SOUTHAMPTON RWY 20 + 510004N 0012010W -
505953N 0011921W -
505848N 0011958W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to
505858N 0012046W -
510004N 0012010W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3360194444,51.00107222220001,609.6 -1.3461549722,50.9829045278,609.6 -1.3415383674,50.982173002,609.6 -1.3370452143,50.9811815632,609.6 -1.3327121667,50.9799383056,609.6 -1.3225805556,50.99808888889999,609.6 -1.3360194444,51.00107222220001,609.6 + + + + +
+ + EGRU013A LEE-ON-SOLENT + 504810N 0010930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
504824N 0010921W -
505049N 0011117W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -
504810N 0010930W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1582839167,50.8028401667,609.6 -1.1571086989,50.80475837249999,609.6 -1.1558333333,50.8066666667,609.6 -1.1880555556,50.8469444444,609.6 -1.1932506097,50.8479990642,609.6 -1.1985905574,50.8487067777,609.6 -1.2040177313,50.84905994170001,609.6 -1.2094735156,50.8490547418,609.6 -1.2148989838,50.8486912341,609.6 -1.220235539,50.8479733448,609.6 -1.2254255503,50.84690882699999,609.6 -1.2304129795,50.845509177,609.6 -1.235143989,50.84378950919999,609.6 -1.2395675256,50.84176839159999,609.6 -1.2436358739,50.83946764480001,609.6 -1.2473051718,50.8369121049,609.6 -1.250535884,50.8341293541,609.6 -1.2532932278,50.831149422,609.6 -1.2555475458,50.82800446,609.6 -1.2572746236,50.8247283936,609.6 -1.2584559467,50.8213565552,609.6 -1.259078896,50.8179253026,609.6 -1.2591368788,50.8144716262,609.6 -1.2586293949,50.8110327501,609.6 -1.2575620362,50.8076457307,609.6 -1.2559464215,50.8043470578,609.6 -1.2538000663,50.8011722618,609.6 -1.2511461895,50.7981555319,609.6 -1.2480134597,50.79532934869999,609.6 -1.244435683,50.7927241356,609.6 -1.2404514373,50.7903679324,609.6 -1.2361036556,50.788286095,609.6 -1.2314391635,50.7865010235,609.6 -1.2265081763,50.7850319225,609.6 -1.2213637601,50.78389459569999,609.6 -1.2160612632,50.78310127679999,609.6 -1.210657724,50.7826604986,609.6 -1.2052112607,50.7825770017,609.6 -1.1997804503,50.78285168429999,609.6 -1.1944237025,50.78348159200001,609.6 -1.1891986355,50.7844599498,609.6 -1.1841614599,50.7857762344,609.6 -1.1793663774,50.7874162864,609.6 -1.1748650004,50.7893624625,609.6 -1.1707057986,50.7915938234,609.6 -1.1669335786,50.7940863583,609.6 -1.1635890021,50.7968132421,609.6 -1.1607081469,50.7997451229,609.6 -1.1582839167,50.8028401667,609.6 + + + + +
+ + EGRU013B LEE-ON-SOLENT RWY 05 + 504641N 0011523W -
504704N 0011559W -
504744N 0011455W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
504721N 0011419W -
504641N 0011523W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2564055556,50.7780111111,609.6 -1.2384847222,50.7892997778,609.6 -1.2421148936,50.7912314979,609.6 -1.2454559012,50.793362658,609.6 -1.2484805278,50.79567594440001,609.6 -1.2663916667,50.7843916667,609.6 -1.2564055556,50.7780111111,609.6 + + + + +
+ + EGRU013C LEE-ON-SOLENT RWY 23 + 505115N 0010919W -
505052N 0010843W -
504947N 0011027W -
505017N 0011052W -
505115N 0010919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1553555556,50.85421388890001,609.6 -1.1809916111,50.83812125,609.6 -1.1742489167,50.82969575,609.6 -1.1453527778,50.8478333333,609.6 -1.1553555556,50.85421388890001,609.6 + + + + +
+ + EGRU014A FLEETLANDS + 504810N 0010929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505007N 0011010W to
505054N 0011304W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
505049N 0011117W -
504824N 0010921W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -
504810N 0010929W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1581221111,50.80279661109999,609.6 -1.1529473377,50.8036983648,609.6 -1.1479446644,50.8049300154,609.6 -1.1431662976,50.8064787134,609.6 -1.1386621169,50.8083283002,609.6 -1.1344791567,50.8104594759,609.6 -1.1306611169,50.8128499992,609.6 -1.1272479066,50.8154749189,609.6 -1.1242752277,50.818306833,609.6 -1.1217742,50.8213161733,609.6 -1.1197710347,50.8244715133,609.6 -1.118286757,50.82773989559999,609.6 -1.1173369832,50.831087175,609.6 -1.1169317532,50.83447837470001,609.6 -1.1170754206,50.8378780514,609.6 -1.1177666027,50.8412506657,609.6 -1.1189981896,50.8445609533,609.6 -1.120757414,50.8477742946,609.6 -1.12302598,50.8508570765,609.6 -1.1257802508,50.8537770454,609.6 -1.1289914919,50.8565036455,609.6 -1.1326261697,50.85900833899999,609.6 -1.1366463005,50.86126490660001,609.6 -1.1410098467,50.8632497227,609.6 -1.1456711573,50.8649420041,609.6 -1.1505814465,50.8663240286,609.6 -1.1556893061,50.867381322,609.6 -1.1609412463,50.8681028098,609.6 -1.1662822588,50.8684809347,609.6 -1.1716563965,50.8685117359,609.6 -1.177007363,50.8681948906,609.6 -1.1822791063,50.8675337178,609.6 -1.1874164094,50.8665351432,609.6 -1.1923654723,50.8652096263,609.6 -1.1970744782,50.8635710497,609.6 -1.201494139,50.8616365735,609.6 -1.2055782131,50.8594264543,609.6 -1.2092839904,50.85696383180001,609.6 -1.2125727394,50.8542744858,609.6 -1.2154101121,50.85138656489999,609.6 -1.2177777778,50.8483333333,609.6 -1.212811389,50.8488638569,609.6 -1.2077876194,50.84909162350001,609.6 -1.2027524466,50.84901454840001,609.6 -1.1977519533,50.8486333371,609.6 -1.1928319027,50.84795147850001,609.6 -1.1880555556,50.8469444444,609.6 -1.1558333333,50.8066666667,609.6 -1.1568187649,50.8046934234,609.6 -1.1581221111,50.80279661109999,609.6 + + + + +
+ + EGRU015A CHICHESTER/GOODWOOD + A circle, 2 NM radius, centred at 505134N 0004533W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7592222222,50.8926428309,609.6 -0.7646350982000001,50.8924662351,609.6 -0.7699904746,50.8919383236,609.6 -0.7752314666999999,50.891064704,609.6 -0.7803024122,50.889854656,609.6 -0.7851494661,50.8883210315,609.6 -0.7897211749000002,50.8864801183,609.6 -0.7939690258000001,50.884351465,609.6 -0.7978479626,50.8819576735,609.6 -0.8013168646000001,50.8793241567,609.6 -0.8043389826999999,50.8764788684,609.6 -0.806882328,50.87345200480001,609.6 -0.8089200087,50.87027568330001,609.6 -0.8104305127,50.8669836003,609.6 -0.8113979313,50.8636106732,609.6 -0.8118121241,50.86019266939999,609.6 -0.8116688211,50.8567658264,609.6 -0.8109696633000001,50.8533664676,609.6 -0.8097221798999999,50.8500306172,609.6 -0.8079397036,50.84679361879999,609.6 -0.8056412243999999,50.8436897616,609.6 -0.8028511848,50.84075191780001,609.6 -0.799599217,50.8380111956,609.6 -0.7959198265,50.8354966104,609.6 -0.7918520250000001,50.83323477929999,609.6 -0.7874389163,50.8312496404,609.6 -0.7827272403999999,50.8295622006,609.6 -0.7777668794,50.8281903142,609.6 -0.7726103315000001,50.8271484956,609.6 -0.767312158,50.8264477661,609.6 -0.7619284093000001,50.8260955385,609.6 -0.7565160352,50.8260955385,609.6 -0.7511322865,50.8264477661,609.6 -0.745834113,50.8271484956,609.6 -0.740677565,50.8281903142,609.6 -0.7357172039999998,50.8295622006,609.6 -0.7310055280999999,50.8312496404,609.6 -0.7265924195,50.83323477929999,609.6 -0.7225246179999999,50.8354966104,609.6 -0.7188452275000001,50.8380111956,609.6 -0.7155932597000001,50.84075191780001,609.6 -0.7128032201,50.8436897616,609.6 -0.7105047409,50.84679361879999,609.6 -0.7087222645000001,50.8500306172,609.6 -0.7074747810999999,50.8533664676,609.6 -0.7067756233999999,50.8567658264,609.6 -0.7066323204,50.86019266939999,609.6 -0.7070465132,50.8636106732,609.6 -0.7080139317999999,50.8669836003,609.6 -0.7095244357000001,50.87027568330001,609.6 -0.7115621164,50.87345200480001,609.6 -0.7141054617,50.8764788684,609.6 -0.7171275798,50.8793241567,609.6 -0.7205964817999999,50.8819576735,609.6 -0.7244754186,50.884351465,609.6 -0.7287232695,50.8864801183,609.6 -0.7332949784,50.8883210315,609.6 -0.7381420322,50.889854656,609.6 -0.7432129777000001,50.891064704,609.6 -0.7484539698,50.8919383236,609.6 -0.7538093463,50.8924662351,609.6 -0.7592222222,50.8926428309,609.6 + + + + +
+ + EGRU015B CHICHESTER/GOODWOOD RWY 06 + 504950N 0004906W -
505017N 0004934W -
505045N 0004826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505018N 0004800W -
504950N 0004906W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8182694444,50.8306472222,609.6 -0.7998924444,50.83823550000001,609.6 -0.8027345357,50.8406427633,609.6 -0.8052225033,50.84320243789999,609.6 -0.8073360277999999,50.8458936944,609.6 -0.8260138889,50.8381805556,609.6 -0.8182694444,50.8306472222,609.6 + + + + +
+ + EGRU015C CHICHESTER/GOODWOOD RWY 24 + 505327N 0004155W -
505300N 0004127W -
505228N 0004244W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505254N 0004313W -
505327N 0004155W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6984805556,50.89073611109999,609.6 -0.7203087222,50.8817591667,609.6 -0.7172734828999999,50.8794467216,609.6 -0.7145805628,50.8769704557,609.6 -0.7122518611,50.8743505833,609.6 -0.690725,50.8832027778,609.6 -0.6984805556,50.89073611109999,609.6 + + + + +
+ + EGRU015D CHICHESTER/GOODWOOD RWY 10 + 505207N 0005003W -
505239N 0004952W -
505226N 0004824W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505155N 0004840W -
505207N 0005003W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8341805556,50.8686861111,609.6 -0.8109841389,50.86530058329999,609.6 -0.8099217521999998,50.8682414599,609.6 -0.8084429209,50.871109396,609.6 -0.8065597222000001,50.87388083329999,609.6 -0.8309749999999999,50.8774444444,609.6 -0.8341805556,50.8686861111,609.6 + + + + +
+ + EGRU015E CHICHESTER/GOODWOOD RWY 28 + 505121N 0004059W -
505049N 0004110W -
505101N 0004231W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505133N 0004224W -
505121N 0004059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6829166667,50.8557472222,609.6 -0.7066161944,50.85923425,609.6 -0.7068499452,50.8562211947,609.6 -0.7075135291999999,50.8532338934,609.6 -0.7086014166999999,50.8502968611,609.6 -0.6861194443999999,50.84698888889999,609.6 -0.6829166667,50.8557472222,609.6 + + + + +
+ + EGRU015F CHICHESTER/GOODWOOD RWY 14 + 505338N 0004857W -
505359N 0004818W -
505314N 0004717W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505253N 0004755W -
505338N 0004857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8157194443999999,50.8937666667,609.6 -0.7987409722000001,50.8813309167,609.6 -0.7954479730999999,50.88349628200001,609.6 -0.7918594971,50.8854649223,609.6 -0.7880047777999999,50.8872207778,609.6 -0.8049527778,50.8996361111,609.6 -0.8157194443999999,50.8937666667,609.6 + + + + +
+ + EGRU015G CHICHESTER/GOODWOOD RWY 32 + 504930N 0004212W -
504909N 0004250W -
504953N 0004350W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505014N 0004312W -
504930N 0004212W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7032166666999999,50.8249722222,609.6 -0.7198981944,50.8372372778,609.6 -0.7232070255,50.8350833674,609.6 -0.7268087460000001,50.8331270285,609.6 -0.7306740278,50.8313841667,609.6 -0.7139638889,50.81910000000001,609.6 -0.7032166666999999,50.8249722222,609.6 + + + + +
+ + EGRU016A SHOREHAM + A circle, 2 NM radius, centred at 505008N 0001750W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2972222222,50.86885130069999,609.6 -0.3026323425,50.86867470430001,609.6 -0.3079849926,50.8681467909,609.6 -0.3132233168,50.86727316830001,609.6 -0.3182916812,50.866063116,609.6 -0.3231362684,50.86452948609999,609.6 -0.3277056511,50.8626885662,609.6 -0.3319513412,50.86055990519999,609.6 -0.3358283055,50.8581661049,609.6 -0.3392954441,50.8555325783,609.6 -0.3423160267,50.8526872793,609.6 -0.3448580805,50.8496604042,609.6 -0.3468947274,50.8464840704,609.6 -0.348404466,50.84319197439999,609.6 -0.3493713957,50.83981903390001,609.6 -0.3497853811,50.8364010162,609.6 -0.3496421542,50.83297415920001,609.6 -0.3489433551,50.8295747861,609.6 -0.347696509,50.8262389215,609.6 -0.3459149416,50.82300190920001,609.6 -0.3436176333,50.81989803849999,609.6 -0.340829014,50.8169601818,609.6 -0.3375787007,50.8142194473,609.6 -0.3339011814,50.8117048508,609.6 -0.329835448,50.8094430095,609.6 -0.3254245824,50.8074578615,609.6 -0.3207153007,50.8057704138,609.6 -0.3157574598,50.804398521,609.6 -0.3106035313,50.80335669750001,609.6 -0.305308049,50.8026559648,609.6 -0.2999270348,50.8023037355,609.6 -0.2945174097,50.8023037355,609.6 -0.2891363954,50.8026559648,609.6 -0.2838409131,50.80335669750001,609.6 -0.2786869846,50.804398521,609.6 -0.2737291437,50.8057704138,609.6 -0.2690198621,50.8074578615,609.6 -0.2646089964,50.8094430095,609.6 -0.260543263,50.8117048508,609.6 -0.2568657438,50.8142194473,609.6 -0.2536154305,50.8169601818,609.6 -0.2508268112,50.81989803849999,609.6 -0.2485295029,50.82300190920001,609.6 -0.2467479354,50.8262389215,609.6 -0.2455010893,50.8295747861,609.6 -0.2448022902,50.83297415920001,609.6 -0.2446590634,50.8364010162,609.6 -0.2450730487,50.83981903390001,609.6 -0.2460399785,50.84319197439999,609.6 -0.2475497171,50.8464840704,609.6 -0.249586364,50.8496604042,609.6 -0.2521284177,50.8526872793,609.6 -0.2551490003,50.8555325783,609.6 -0.258616139,50.8581661049,609.6 -0.2624931032,50.86055990519999,609.6 -0.2667387934,50.8626885662,609.6 -0.2713081761,50.86452948609999,609.6 -0.2761527632,50.866063116,609.6 -0.2812211277,50.86727316830001,609.6 -0.2864594519,50.8681467909,609.6 -0.291812102,50.86867470430001,609.6 -0.2972222222,50.86885130069999,609.6 + + + + +
+ + EGRU016B SHOREHAM RWY 02 + 504721N 0001907W -
504733N 0001954W -
504824N 0001923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504812N 0001836W -
504721N 0001907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3185777778,50.78930277780001,609.6 -0.3098738056,50.8032385556,609.6 -0.3144202236,50.8040923247,609.6 -0.3188268489,50.8052022003,609.6 -0.3230578611,50.8065591389,609.6 -0.3317638889,50.7926138889,609.6 -0.3185777778,50.78930277780001,609.6 + + + + +
+ + EGRU016C SHOREHAM RWY 20 + 505257N 0001632W -
505245N 0001544W -
505153N 0001617W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505204N 0001705W -
505257N 0001632W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2755388889,50.8825166667,609.6 -0.2846998611,50.8678939167,609.6 -0.2801439923,50.8670472756,609.6 -0.2757274932,50.86594399400001,609.6 -0.2714863889,50.8645930833,609.6 -0.2623277778,50.87920555560001,609.6 -0.2755388889,50.8825166667,609.6 + + + + +
+ + EGRU016D SHOREHAM RWY 02G + 504726N 0001901W -
504737N 0001949W -
504823N 0001920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504811N 0001833W -
504726N 0001901W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3169555556,50.79042222220001,609.6 -0.3090648333,50.80311575,609.6 -0.3136313441,50.8039237264,609.6 -0.3180645222,50.8049890836,609.6 -0.3223283333,50.8063031667,609.6 -0.3301472222,50.7937194444,609.6 -0.3169555556,50.79042222220001,609.6 + + + + +
+ + EGRU016E SHOREHAM RWY 20G + 505257N 0001630W -
505245N 0001542W -
505152N 0001615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505204N 0001703W -
505257N 0001630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2749555556,50.88238888890001,609.6 -0.2840571944,50.8677914722,609.6 -0.2795191306,50.8669086685,609.6 -0.2751254908,50.8657704377,609.6 -0.2709121111,50.86438605560001,609.6 -0.2617388889,50.8790916667,609.6 -0.2749555556,50.88238888890001,609.6 + + + + +
+ + EGRU016F SHOREHAM RWY 06 + 504834N 0002129W -
504903N 0002152W -
504924N 0002046W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504856N 0002021W -
504834N 0002129W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3579972222,50.8094305556,609.6 -0.3390849167,50.8154169167,609.6 -0.3417847915,50.8178920876,609.6 -0.3441212182,50.82051149739999,609.6 -0.3460750833,50.82325377780001,609.6 -0.3643305555999999,50.817475,609.6 -0.3579972222,50.8094305556,609.6 + + + + +
+ + EGRU016G SHOREHAM RWY 24 + 505136N 0001347W -
505107N 0001324W -
505041N 0001448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505110N 0001508W -
505136N 0001347W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2297,50.8599916667,609.6 -0.2523026944,50.8528699444,609.6 -0.2500184701,50.8502315888,609.6 -0.2481200116,50.8474734479,609.6 -0.2466227778,50.8446180556,609.6 -0.2233611111,50.85194722220001,609.6 -0.2297,50.8599916667,609.6 + + + + +
+ + EGRU016H SHOREHAM RWY 13 + 505137N 0002125W -
505204N 0002056W -
505137N 0001956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505113N 0002029W -
505137N 0002125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3568833332999999,50.8602972222,609.6 -0.3414891667,50.85353133329999,609.6 -0.3387353645,50.85599701280001,609.6 -0.3356396771,50.8582945513,609.6 -0.3322275556,50.8604050278,609.6 -0.3487722222,50.8676777778,609.6 -0.3568833332999999,50.8602972222,609.6 + + + + +
+ + EGRU016I SHOREHAM RWY 31 + 504851N 0001339W -
504825N 0001408W -
504856N 0001519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504924N 0001454W -
504851N 0001339W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2274555556,50.8142416667,609.6 -0.2482630278,50.8234243611,609.6 -0.250200315,50.8206661153,609.6 -0.2525237726,50.8180303055,609.6 -0.2552142778,50.8155385833,609.6 -0.2355555556,50.80686388889999,609.6 -0.2274555556,50.8142416667,609.6 + + + + +
+ + EGRU017A LYDD + A circle, 2 NM radius, centred at 505722N 0005621E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9391499999999999,50.9894700535,609.6 0.9337258699999998,50.98929346020001,609.6 0.9283593595,50.9887655562,609.6 0.9231074720000001,50.9878919491,609.6 0.9180259856999999,50.9866819185,609.6 0.9131688582,50.98514831619999,609.6 0.9085876498,50.98330742980001,609.6 0.9043309744,50.981178808,609.6 0.900443982,50.9787850521,609.6 0.8969678786,50.97615157509999,609.6 0.8939394896,50.9733063304,609.6 0.8913908701,50.97027951379999,609.6 0.8893489674,50.9671032423,609.6 0.8878353379,50.9638112119,609.6 0.8868659227,50.9604383396,609.6 0.886450883,50.95702039220001,609.6 0.8865944969,50.9535936066,609.6 0.8872951194000001,50.9501943055,609.6 0.8885452053000001,50.9468585126,609.6 0.8903313938000001,50.9436215708,609.6 0.8926346547,50.9405177686,609.6 0.8954304945,50.9375799776,609.6 0.8986892193,50.9348393051,609.6 0.9023762517,50.93232476600001,609.6 0.9064524989,50.9300629769,609.6 0.9108747678000001,50.92807787510001,609.6 0.9155962214000001,50.926390467,609.6 0.9205668744000001,50.9250186065,609.6 0.92573412,50.9239768078,609.6 0.9310432837999999,50.9232760917,609.6 0.9364381998,50.9229238708,609.6 0.9418618002,50.9229238708,609.6 0.9472567162000001,50.9232760917,609.6 0.95256588,50.9239768078,609.6 0.9577331255999999,50.9250186065,609.6 0.9627037785999999,50.926390467,609.6 0.9674252321999999,50.92807787510001,609.6 0.9718475011,50.9300629769,609.6 0.9759237482999999,50.93232476600001,609.6 0.9796107807,50.9348393051,609.6 0.9828695055,50.9375799776,609.6 0.9856653453000001,50.9405177686,609.6 0.9879686062,50.9436215708,609.6 0.9897547947000001,50.9468585126,609.6 0.9910048806,50.9501943055,609.6 0.9917055031000001,50.9535936066,609.6 0.991849117,50.95702039220001,609.6 0.9914340773,50.9604383396,609.6 0.9904646620999999,50.9638112119,609.6 0.9889510325999999,50.9671032423,609.6 0.9869091299,50.97027951379999,609.6 0.9843605104000001,50.9733063304,609.6 0.9813321214000001,50.97615157509999,609.6 0.977856018,50.9787850521,609.6 0.9739690256,50.981178808,609.6 0.9697123502,50.98330742980001,609.6 0.9651311417999999,50.98514831619999,609.6 0.9602740143,50.9866819185,609.6 0.9551925279999999,50.9878919491,609.6 0.9499406404999999,50.9887655562,609.6 0.9445741300000001,50.98929346020001,609.6 0.9391499999999999,50.9894700535,609.6 + + + + +
+ + EGRU017B LYDD RWY 03 + 505437N 0005403E -
505454N 0005320E -
505551N 0005418E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to
505534N 0005501E -
505437N 0005403E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9009277778,50.9102333333,609.6 0.9169214722,50.9259866667,609.6 0.9127054288000001,50.92737516899999,609.6 0.9087043515999998,50.9289980997,609.6 0.9049507778,50.93084224999999,609.6 0.8889638889,50.9150916667,609.6 0.9009277778,50.9102333333,609.6 + + + + +
+ + EGRU017C LYDD RWY 21 + 510007N 0005838E -
505949N 0005921E -
505853N 0005824E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to
505911N 0005741E -
510007N 0005838E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9771694444000001,51.0018333333,609.6 0.9614053611,50.9863595278,609.6 0.9656253747999999,50.98496937670001,609.6 0.9696293844,50.98334461529999,609.6 0.97338475,50.9814985,609.6 0.9891555556,50.996975,609.6 0.9771694444000001,51.0018333333,609.6 + + + + +
+ + EGRU019A LERWICK/TINGWALL + A circle, 2 NM radius, centred at 601131N 0011437W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2436111111,60.22518927309999,609.6 -1.25048308,60.2250128939,609.6 -1.2572819849,60.2244856317,609.6 -1.2639355456,60.22361309210001,609.6 -1.2703730408,60.2224045513,609.6 -1.2765260659,60.22087285609999,609.6 -1.2823292652,60.2190342866,609.6 -1.2877210302,60.2169083816,609.6 -1.2926441565,60.2145177293,609.6 -1.2970464527,60.2118877258,609.6 -1.3008812932,60.2090463035,609.6 -1.3041081112,60.2060236326,609.6 -1.3066928252,60.20285179940001,609.6 -1.3086081946,60.1995644641,609.6 -1.3098341021,60.19619650240001,609.6 -1.3103577589,60.19278363469999,609.6 -1.3101738317,60.18936204650001,609.6 -1.3092844896,60.1859680046,609.6 -1.3076993726,60.1826374726,609.6 -1.3054354794,60.17940573060001,609.6 -1.30251698,60.176307002,609.6 -1.2989749513,60.1733740921,609.6 -1.2948470426,60.1706380425,609.6 -1.2901770716,60.1681278037,609.6 -1.2850145576,60.1658699305,609.6 -1.2794141959,60.16388830319999,609.6 -1.2734352793,60.162203876,609.6 -1.2671410726,60.16083445780001,609.6 -1.2605981468,60.1597945248,609.6 -1.2538756796,60.1590950691,609.6 -1.2470447298,60.1587434834,609.6 -1.2401774924,60.1587434834,609.6 -1.2333465426,60.1590950691,609.6 -1.2266240754,60.1597945248,609.6 -1.2200811496,60.16083445780001,609.6 -1.2137869429,60.162203876,609.6 -1.2078080264,60.16388830319999,609.6 -1.2022076647,60.1658699305,609.6 -1.1970451506,60.1681278037,609.6 -1.1923751796,60.1706380425,609.6 -1.1882472709,60.1733740921,609.6 -1.1847052422,60.176307002,609.6 -1.1817867428,60.17940573060001,609.6 -1.1795228496,60.1826374726,609.6 -1.1779377326,60.1859680046,609.6 -1.1770483906,60.18936204650001,609.6 -1.1768644633,60.19278363469999,609.6 -1.1773881202,60.19619650240001,609.6 -1.1786140277,60.1995644641,609.6 -1.180529397,60.20285179940001,609.6 -1.183114111,60.2060236326,609.6 -1.1863409291,60.2090463035,609.6 -1.1901757695,60.2118877258,609.6 -1.1945780657,60.2145177293,609.6 -1.1995011921,60.2169083816,609.6 -1.204892957,60.2190342866,609.6 -1.2106961563,60.22087285609999,609.6 -1.2168491815,60.2224045513,609.6 -1.2232866766,60.22361309210001,609.6 -1.2299402373,60.2244856317,609.6 -1.2367391422,60.2250128939,609.6 -1.2436111111,60.22518927309999,609.6 + + + + +
+ + EGRU019B LERWICK/TINGWALL RWY 02 + 600839N 0011524W -
600847N 0011627W -
600939N 0011603W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to
600932N 0011500W -
600839N 0011524W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2567777778,60.1442333333,609.6 -1.2499103611,60.15884788890001,609.6 -1.2558708651,60.15926527530001,609.6 -1.2617318323,60.1599485109,609.6 -1.2674456667,60.1608920556,609.6 -1.2743027778,60.1462833333,609.6 -1.2567777778,60.1442333333,609.6 + + + + +
+ + EGRU019C LERWICK/TINGWALL RWY 20 + 601424N 0011349W -
601417N 0011245W -
601323N 0011311W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to
601330N 0011414W -
601424N 0011349W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2301611111,60.2400916667,609.6 -1.2372617778,60.22503875,609.6 -1.2312903432,60.22461891820001,609.6 -1.2254195327,60.2239327561,609.6 -1.2196972778,60.2229858889,609.6 -1.2125861111,60.23804444440001,609.6 -1.2301611111,60.2400916667,609.6 + + + + +
+ + EGRU020 HMP CHANNINGS WOOD + 503110N 0033918W -
503108N 0033842W -
503054N 0033836W -
503029N 0033847W -
503022N 0033920W -
503034N 0033946W -
503049N 0033947W -
503110N 0033918W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 291 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.655,50.5194,213.36 -3.6629972222,50.513475,213.36 -3.6626555556,50.50954444440001,213.36 -3.655516666700001,50.5061305556,213.36 -3.6463638889,50.5079861111,213.36 -3.6433027778,50.5149527778,213.36 -3.645099999999999,50.51877222220001,213.36 -3.655,50.5194,213.36 + + + + +
+ + EGRU021 HMP DARTMOOR + 503318N 0035946W -
503312N 0035925W -
503259N 0035917W -
503247N 0035924W -
503235N 0035957W -
503308N 0040020W -
503318N 0035946W
Upper limit: 1900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 1403 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.996130555600001,50.5549111111,579.12 -4.0056361111,50.5521527778,579.12 -3.9991277778,50.5430111111,579.12 -3.9899416667,50.54638333330001,579.12 -3.9880027778,50.54969722220001,579.12 -3.9904138889,50.5534277778,579.12 -3.996130555600001,50.5549111111,579.12 + + + + +
+ + EGRU022 HMP EXETER + 504400N 0033157W -
504357N 0033136W -
504332N 0033124W -
504325N 0033218W -
504352N 0033230W -
504400N 0033157W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 184 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5325777778,50.7332972222,182.88 -3.5415472222,50.731125,182.88 -3.5382944444,50.72348888889999,182.88 -3.5232972222,50.7256,182.88 -3.526575,50.7326305556,182.88 -3.5325777778,50.7332972222,182.88 + + + + +
+ + EGRU023 HMP GUYS MARSH + 505925N 0021325W -
505928N 0021252W -
505901N 0021229W -
505842N 0021316W -
505909N 0021348W -
505925N 0021325W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 346 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2236361111,50.9901722222,243.84 -2.2300527778,50.98580833329999,243.84 -2.2209777778,50.97821111110001,243.84 -2.2080888889,50.9837472222,243.84 -2.2145111111,50.9911916667,243.84 -2.2236361111,50.9901722222,243.84 + + + + +
+ + EGRU024 HMP ISLE OF WIGHT + 504308N 0011912W -
504318N 0011810W -
504227N 0011750W -
504216N 0011840W -
504308N 0011912W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 157 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3200083333,50.7187833333,182.88 -1.3110416667,50.7045388889,182.88 -1.2973027778,50.7075833333,182.88 -1.3026555556,50.7215638889,182.88 -1.3200083333,50.7187833333,182.88 + + + + +
+ + EGRU025 HMP LEWES + 505243N 0000018W -
505231N 0000006E -
505216N 0000007E -
505200N 0000032W -
505228N 0000058W -
505243N 0000018W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 207 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0049527778,50.8787138889,213.36 -0.01605,50.874425,213.36 -0.0089611111,50.86659999999999,213.36 0.00205,50.8709777778,213.36 0.0016305556,50.8752805556,213.36 -0.0049527778,50.8787138889,213.36 + + + + +
+ + EGRU026 HMP PORTLAND + 503323N 0022549W -
503325N 0022513W -
503306N 0022455W -
503247N 0022444W -
503243N 0022529W -
503306N 0022556W -
503323N 0022549W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 382 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.430325,50.5564944444,243.84 -2.43215,50.5517,243.84 -2.4248138889,50.54528055559999,243.84 -2.4123027778,50.5464833333,243.84 -2.4152,50.5516916667,243.84 -2.4202333333,50.55705,243.84 -2.430325,50.5564944444,243.84 + + + + +
+ + EGRU027 HMP THE VERNE + 503359N 0022615W -
503358N 0022546W -
503333N 0022528W -
503320N 0022612W -
503326N 0022617W -
503327N 0022640W -
503351N 0022636W -
503359N 0022615W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 476 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4375472222,50.56629444440001,274.32 -2.4433861111,50.5640555556,274.32 -2.4445305556,50.55748055559999,274.32 -2.4380888889,50.5572861111,274.32 -2.4366027778,50.5555277778,274.32 -2.4245555556,50.5591222222,274.32 -2.4293055556,50.5659888889,274.32 -2.4375472222,50.56629444440001,274.32 + + + + +
+ + EGRU101A HAVERFORDWEST + A circle, 2 NM radius, centred at 515000N 0045739W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9608472222,51.86660115400001,609.6 -4.9663762085,51.8664245833,609.6 -4.9718464575,51.8658967469,609.6 -4.97719986,51.8650232521,609.6 -4.9823795559,51.8638133777,609.6 -4.9873305421,51.8622799751,609.6 -4.9920002595,51.8604393304,609.6 -4.9963391531,51.85831099090001,609.6 -5.0003012001,51.85591755630001,609.6 -5.0038443986,51.8532844373,609.6 -5.0069312133,51.85043958459999,609.6 -5.0095289721,51.8474131912,609.6 -5.0116102105,51.8442373706,609.6 -5.0131529595,51.84094581480001,609.6 -5.0141409747,51.8375734365,609.6 -5.0145639039,51.83415599749999,609.6 -5.0144173916,51.83072972970001,609.6 -5.0137031196,51.82733095030001,609.6 -5.0124287842,51.82399567689999,609.6 -5.010608009,51.8207592466,609.6 -5.0082601956,51.8176559415,609.6 -5.0054103137,51.8147186271,609.6 -5.0020886333,51.8119784046,609.6 -4.9983304008,51.8094642829,609.6 -4.9941754641,51.8072028728,609.6 -4.9896678499,51.80521810659999,609.6 -4.9848552974,51.8035309858,609.6 -4.9797887545,51.80215936050001,609.6 -4.9745218403,51.8011177411,609.6 -4.9691102802,51.8004171461,609.6 -4.9636113201,51.80006498619999,609.6 -4.9580831243,51.80006498619999,609.6 -4.9525841643,51.8004171461,609.6 -4.9471726042,51.8011177411,609.6 -4.9419056899,51.80215936050001,609.6 -4.9368391471,51.8035309858,609.6 -4.9320265946,51.80521810659999,609.6 -4.9275189803,51.8072028728,609.6 -4.9233640436,51.8094642829,609.6 -4.9196058111,51.8119784046,609.6 -4.9162841307,51.8147186271,609.6 -4.9134342489,51.8176559415,609.6 -4.9110864354,51.8207592466,609.6 -4.9092656602,51.82399567689999,609.6 -4.9079913248,51.82733095030001,609.6 -4.9072770529,51.83072972970001,609.6 -4.9071305405,51.83415599749999,609.6 -4.9075534697,51.8375734365,609.6 -4.908541485,51.84094581480001,609.6 -4.9100842339,51.8442373706,609.6 -4.9121654723,51.8474131912,609.6 -4.9147632311,51.85043958459999,609.6 -4.9178500458,51.8532844373,609.6 -4.9213932444,51.85591755630001,609.6 -4.9253552913,51.85831099090001,609.6 -4.929694185,51.8604393304,609.6 -4.9343639023,51.8622799751,609.6 -4.9393148885,51.8638133777,609.6 -4.9444945845,51.8650232521,609.6 -4.9498479869,51.8658967469,609.6 -4.9553182359,51.8664245833,609.6 -4.9608472222,51.86660115400001,609.6 + + + + +
+ + EGRU101B HAVERFORDWEST RWY 03 + 514716N 0045940W -
514732N 0050025W -
514825N 0045937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
514809N 0045851W -
514716N 0045940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9943083333,51.7878444444,609.6 -4.9809063333,51.8024292222,609.6 -4.9853153742,51.8036751517,609.6 -4.9895255747,51.80516225289999,609.6 -4.9935026944,51.80687844439999,609.6 -5.0068972222,51.79229722220001,609.6 -4.9943083333,51.7878444444,609.6 + + + + +
+ + EGRU101C HAVERFORDWEST RWY 21 + 515243N 0045539W -
515227N 0045454W -
515135N 0045541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
515151N 0045627W -
515243N 0045539W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9275583333,51.8785055556,609.6 -4.9407586667,51.86418891669999,609.6 -4.9363448359,51.86294117239999,609.6 -4.9321309303,51.8614520004,609.6 -4.9281513056,51.8597335556,609.6 -4.9149444444,51.8740527778,609.6 -4.9275583333,51.8785055556,609.6 + + + + +
+ + EGRU101D HAVERFORDWEST RWY 09 + 514940N 0050222W -
515012N 0050224W -
515015N 0050051W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
514942N 0050050W -
514940N 0050222W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0394888889,51.82773611110001,609.6 -5.0139970278,51.8284296389,609.6 -5.0144928085,51.8314198647,609.6 -5.0145512565,51.8344256075,609.6 -5.0141718056,51.8374223611,609.6 -5.0401138889,51.83671666669999,609.6 -5.0394888889,51.82773611110001,609.6 + + + + +
+ + EGRU101E HAVERFORDWEST RWY 27 + 515027N 0045311W -
514955N 0045309W -
514953N 0045426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
515025N 0045430W -
515027N 0045311W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.886525,51.8408111111,609.6 -4.9082875833,51.8402431944,609.6 -4.9074941979,51.8372777002,609.6 -4.9071359293,51.8342799592,609.6 -4.9072156111,51.8312744167,609.6 -4.8859027778,51.8318305556,609.6 -4.886525,51.8408111111,609.6 + + + + +
+ + EGRU103A SWANSEA + A circle, 2 NM radius, centred at 513619N 0040404W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0677777778,51.6385691199,609.6 -4.0732789905,51.6383925433,609.6 -4.0787217619,51.6378646894,609.6 -4.0840482758,51.6369911656,609.6 -4.0892019586,51.63578125080001,609.6 -4.0941280843,51.63424779660001,609.6 -4.0987743581,51.6324070894,609.6 -4.1030914745,51.6302786768,609.6 -4.1070336417,51.6278851591,609.6 -4.1105590688,51.6252519474,609.6 -4.1136304084,51.6224069933,609.6 -4.1162151518,51.6193804903,609.6 -4.1182859716,51.61620455290001,609.6 -4.1198210079,51.61291287409999,609.6 -4.1208040969,51.6095403677,609.6 -4.1212249367,51.606122797,609.6 -4.1210791924,51.6026963949,609.6 -4.120368536,51.5992974802,609.6 -4.1191006239,51.595962072,609.6 -4.1172890099,51.592725509,609.6 -4.1149529973,51.5896220749,609.6 -4.1121174298,51.58668463670001,609.6 -4.1088124245,51.58394429730001,609.6 -4.1050730509,51.5814300673,609.6 -4.1009389566,51.57916855869999,609.6 -4.0964539477,51.5771837053,609.6 -4.0916655245,51.57549650990001,609.6 -4.0866243798,51.5741248235,609.6 -4.0813838645,51.5730831575,609.6 -4.0759994259,51.572382531,609.6 -4.0705280237,51.5720303553,609.6 -4.0650275318,51.5720303553,609.6 -4.0595561297,51.572382531,609.6 -4.054171691,51.5730831575,609.6 -4.0489311758,51.5741248235,609.6 -4.0438900311,51.57549650990001,609.6 -4.0391016078,51.5771837053,609.6 -4.0346165989,51.57916855869999,609.6 -4.0304825047,51.5814300673,609.6 -4.026743131,51.58394429730001,609.6 -4.0234381258,51.58668463670001,609.6 -4.0206025582,51.5896220749,609.6 -4.0182665456,51.592725509,609.6 -4.0164549317,51.595962072,609.6 -4.0151870195,51.5992974802,609.6 -4.0144763632,51.6026963949,609.6 -4.0143306189,51.606122797,609.6 -4.0147514587,51.6095403677,609.6 -4.0157345476,51.61291287409999,609.6 -4.017269584,51.61620455290001,609.6 -4.0193404037,51.6193804903,609.6 -4.0219251472,51.6224069933,609.6 -4.0249964868,51.6252519474,609.6 -4.0285219138,51.6278851591,609.6 -4.0324640811,51.6302786768,609.6 -4.0367811974,51.6324070894,609.6 -4.0414274713,51.63424779660001,609.6 -4.0463535969,51.63578125080001,609.6 -4.0515072798,51.6369911656,609.6 -4.0568337937,51.6378646894,609.6 -4.0622765651,51.6383925433,609.6 -4.0677777778,51.6385691199,609.6 + + + + +
+ + EGRU103B SWANSEA RWY 04 + 513341N 0040638W -
513400N 0040720W -
513453N 0040618W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513434N 0040536W -
513341N 0040638W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1105694444,51.5614305556,609.6 -4.0933516667,51.5760447778,609.6 -4.0974772875,51.5775992074,609.6 -4.1013615228,51.5793789018,609.6 -4.1049727778,51.58136938889999,609.6 -4.1221888889,51.5667527778,609.6 -4.1105694444,51.5614305556,609.6 + + + + +
+ + EGRU103C SWANSEA RWY 22 + 513854N 0040133W -
513835N 0040052W -
513745N 0040150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513804N 0040232W -
513854N 0040133W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0259555556,51.6483027778,609.6 -4.0422406389,51.6345286389,609.6 -4.0381074205,51.632975828,609.6 -4.0342163026,51.631197314,609.6 -4.030599,51.62920761110001,609.6 -4.0143111111,51.6429805556,609.6 -4.0259555556,51.6483027778,609.6 + + + + +
+ + EGRU103D SWANSEA RWY 10 + 513606N 0040854W -
513638N 0040848W -
513632N 0040715W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513559N 0040714W -
513606N 0040854W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1483194444,51.6016305556,609.6 -4.1204896111,51.5997253611,609.6 -4.1210842429,51.602737017,609.6 -4.1212361072,51.605769878,609.6 -4.1209438611,51.60879875,609.6 -4.1467305556,51.6105638889,609.6 -4.1483194444,51.6016305556,609.6 + + + + +
+ + EGRU103E SWANSEA RWY 28 + 513600N 0035931W -
513527N 0035937W -
513534N 0040106W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513605N 0040053W -
513600N 0035931W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9918916667,51.5998777778,609.6 -4.0146683056,51.6014628333,609.6 -4.015448363,51.5984676719,609.6 -4.0166629251,51.5955291688,609.6 -4.0183018333,51.5926717222,609.6 -3.9934777778,51.5909444444,609.6 -3.9918916667,51.5998777778,609.6 + + + + +
+ + EGRU104A ST ATHAN + 512532N 0032328W -
512241N 0032410W thence clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to -
512532N 0032328W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3911111111,51.4255555556,609.6 -3.394727747500001,51.4281636406,609.6 -3.3987267963,51.4305415517,609.6 -3.4030987649,51.4326475738,609.6 -3.4077965855,51.4344590111,609.6 -3.4127696603,51.4359563401,609.6 -3.4179644073,51.4371234209,609.6 -3.4233248408,51.4379476723,609.6 -3.428793177899999,51.43842020819999,609.6 -3.4343104649,51.4385359342,609.6 -3.4398172168,51.43829360260001,609.6 -3.445254063,51.437695826,609.6 -3.4505623917,51.4367490491,609.6 -3.4556849849,51.4354634786,609.6 -3.4605666395,51.4338529727,609.6 -3.465154765,51.4319348906,609.6 -3.4693999519,51.42972990429999,609.6 -3.4732565058,51.42726177509999,609.6 -3.476682940299999,51.4245570954,609.6 -3.4796424223,51.4216450019,609.6 -3.4821031677,51.4185568596,609.6 -3.4840387809,51.4153259234,609.6 -3.4854285349,51.4119869789,609.6 -3.4862575909,51.40857596650001,609.6 -3.4865171524,51.40512959469999,609.6 -3.4862045549,51.40168494419999,609.6 -3.4853232893,51.39827906879999,609.6 -3.4838829581,51.3949485973,609.6 -3.4818991679,51.3917293395,609.6 -3.4793933557,51.3886559024,609.6 -3.4763925551,51.38576131840001,609.6 -3.4729291017,51.3830766918,609.6 -3.4690402832,51.3806308656,609.6 -3.4647679371,51.3784501128,609.6 -3.4601580005,51.37655785539999,609.6 -3.4552600171,51.3749744143,609.6 -3.4501266063,51.3737167921,609.6 -3.4448129005,51.3727984916,609.6 -3.4393759557,51.3722293717,609.6 -3.4338741428,51.3720155421,609.6 -3.4283665243,51.3721592983,609.6 -3.4229122247,51.37265909719999,609.6 -3.4175698,51.3735095732,609.6 -3.412396612699999,51.37470159559999,609.6 -3.4074482194,51.3762223661,609.6 -3.4027777778,51.3780555556,609.6 -3.3911111111,51.4255555556,609.6 + + + + +
+ + EGRU104B ST ATHAN RWY 07 + 512308N 0033043W -
512339N 0033058W -
512400N 0032909W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to
512329N 0032854W -
512308N 0033043W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.511936111099999,51.38549999999999,609.6 -3.4816345,51.39129580560001,609.6 -3.483453917,51.3940757942,609.6 -3.4848655896,51.39694704319999,609.6 -3.4858579444,51.3998861944,609.6 -3.5161222222,51.3940972222,609.6 -3.511936111099999,51.38549999999999,609.6 + + + + +
+ + EGRU104C ST ATHAN RWY 25 + 512530N 0032116W -
512459N 0032101W -
512428N 0032344W -
512503N 0032335W -
512530N 0032116W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3543944444,51.424925,609.6 -3.3930726111,51.4175764444,609.6 -3.3954943889,51.4077211111,609.6 -3.3502,51.4163277778,609.6 -3.3543944444,51.424925,609.6 + + + + +
+ + EGRU105A CARDIFF + 512532N 0032328W thence clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to
512241N 0032410W -
512532N 0032328W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3911111111,51.4255555556,609.6 -3.4027777778,51.3780555556,609.6 -3.3998652394,51.3747004374,609.6 -3.3964158735,51.3715489884,609.6 -3.392519759699999,51.3686086909,609.6 -3.3882097622,51.36590428489999,609.6 -3.3835222082,51.36345852119999,609.6 -3.3784965819,51.36129197170001,609.6 -3.3731751922,51.3594228567,609.6 -3.367602817999999,51.3578668934,609.6 -3.361826333399999,51.35663716399999,609.6 -3.3558943152,51.35574400710001,609.6 -3.349856637899999,51.355194931,609.6 -3.3437640568,51.3549945514,609.6 -3.337667784999999,51.35514455260001,609.6 -3.3316190667,51.35564367369999,609.6 -3.3256687493,51.3564877191,609.6 -3.3198668596,51.3576695933,609.6 -3.3142621866,51.3591793603,609.6 -3.3089018737,51.36100432629999,609.6 -3.303831025,51.3631291457,609.6 -3.2990923271,51.36553594940001,609.6 -3.2947256915,51.36820449380001,609.6 -3.2907679193,51.37111233020001,609.6 -3.2872523906,51.3742349926,609.6 -3.284208783,51.377546202,609.6 -3.2816628197,51.3810180874,609.6 -3.2796360502,51.3846214184,609.6 -3.2781456658,51.3883258514,609.6 -3.277204351,51.39210018400001,609.6 -3.2768201726,51.3959126172,609.6 -3.2769965071,51.3997310233,609.6 -3.2777320074,51.4035232161,609.6 -3.279020609999999,51.40725722260001,609.6 -3.2808515811,51.4109015527,609.6 -3.283209603,51.4144254654,609.6 -3.2860748989,51.4177992282,609.6 -3.289423397200001,51.42099436940001,609.6 -3.2932269306,51.4239839189,609.6 -3.2974534725,51.4267426368,609.6 -3.3020674054,51.42924722790001,609.6 -3.3070298211,51.4314765391,609.6 -3.3122988491,51.43341173959999,609.6 -3.3178300112,51.4350364804,609.6 -3.3235765985,51.4363370339,609.6 -3.329490068200001,51.43730241069999,609.6 -3.3355204563,51.4379244528,609.6 -3.341616803,51.4381979032,609.6 -3.3477275864,51.4381204511,609.6 -3.353801161799999,51.437692751,609.6 -3.3597862013,51.4369184174,609.6 -3.3656321314,51.435803994,609.6 -3.3712895632,51.4343588982,609.6 -3.3767107132,51.4325953402,609.6 -3.3818498086,51.4305282199,609.6 -3.3866634765,51.4281749996,609.6 -3.3911111111,51.4255555556,609.6 + + + + +
+ + EGRU105B CARDIFF RWY 12 + 512500N 0032523W -
512529N 0032500W -
512502N 0032335W -
512429N 0032344W -
512500N 0032523W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4230194444,51.4166861111,609.6 -3.395426,51.40799941670001,609.6 -3.3931304444,51.4173411111,609.6 -3.416541666700001,51.4247111111,609.6 -3.4230194444,51.4166861111,609.6 + + + + +
+ + EGRU105C CARDIFF RWY 30 + 512234N 0031546W -
512205N 0031610W -
512226N 0031715W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to
512255N 0031652W -
512234N 0031546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2628444444,51.3761972222,609.6 -3.2810616111,51.3819633056,609.6 -3.2829113154,51.3791942869,609.6 -3.2850748667,51.3765158529,609.6 -3.2875409722,51.3739419167,609.6 -3.2693111111,51.3681722222,609.6 -3.2628444444,51.3761972222,609.6 + + + + +
+ + EGRU106A BRISTOL + A circle, 2.5 NM radius, centred at 512258N 0024309W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7191,51.4242851807,609.6 -2.725241868,51.4241074951,609.6 -2.731331194,51.42357595829999,609.6 -2.7373158889,51.4226951174,609.6 -2.7431447661,51.421472507,609.6 -2.7487679819,51.4199185848,609.6 -2.7541374654,51.4180466408,609.6 -2.7592073311,51.41587268349999,609.6 -2.7639342736,51.41341530139999,609.6 -2.7682779384,51.4106955036,609.6 -2.772201267,51.4077365385,609.6 -2.7756708136,51.4045636943,609.6 -2.7786570288,51.4012040819,609.6 -2.7811345104,51.3976864016,609.6 -2.7830822176,51.3940406978,609.6 -2.7844836469,51.3902981006,609.6 -2.7853269691,51.3864905603,609.6 -2.7856051262,51.3826505733,609.6 -2.7853158864,51.3788109052,609.6 -2.7844618587,51.3750043104,609.6 -2.7830504661,51.3712632532,609.6 -2.7810938767,51.3676196314,609.6 -2.7786088966,51.3641045045,609.6 -2.7756168221,51.36074782950001,609.6 -2.7721432548,51.357578207,609.6 -2.7682178809,51.3546226381,609.6 -2.7638742162,51.35190629520001,609.6 -2.7591493189,51.3494523093,609.6 -2.7540834738,51.3472815737,609.6 -2.7487198497,51.3454125672,609.6 -2.7431041323,51.3438611982,609.6 -2.7372841373,51.3426406699,609.6 -2.7313094058,51.341761369,609.6 -2.7252307852,51.34123077780001,609.6 -2.7191,51.341053411,609.6 -2.7129692148,51.34123077780001,609.6 -2.7068905942,51.341761369,609.6 -2.7009158627,51.3426406699,609.6 -2.6950958677,51.3438611982,609.6 -2.6894801503,51.3454125672,609.6 -2.6841165262,51.3472815737,609.6 -2.6790506811,51.3494523093,609.6 -2.6743257838,51.35190629520001,609.6 -2.6699821191,51.3546226381,609.6 -2.6660567452,51.357578207,609.6 -2.6625831779,51.36074782950001,609.6 -2.6595911034,51.3641045045,609.6 -2.6571061233,51.3676196314,609.6 -2.6551495339,51.3712632532,609.6 -2.6537381413,51.3750043104,609.6 -2.6528841136,51.3788109052,609.6 -2.6525948738,51.3826505733,609.6 -2.6528730309,51.3864905603,609.6 -2.6537163531,51.3902981006,609.6 -2.6551177824,51.3940406978,609.6 -2.6570654896,51.3976864016,609.6 -2.6595429712,51.4012040819,609.6 -2.6625291864,51.4045636943,609.6 -2.665998733,51.4077365385,609.6 -2.6699220616,51.4106955036,609.6 -2.6742657264,51.41341530139999,609.6 -2.6789926689,51.41587268349999,609.6 -2.6840625346,51.4180466408,609.6 -2.6894320181,51.4199185848,609.6 -2.6950552339,51.421472507,609.6 -2.7008841111,51.4226951174,609.6 -2.706868806,51.42357595829999,609.6 -2.712958132,51.4241074951,609.6 -2.7191,51.4242851807,609.6 + + + + +
+ + EGRU106B BRISTOL RWY 09 + 512229N 0024817W -
512302N 0024820W -
512304N 0024708W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to
512232N 0024705W -
512229N 0024817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8047333333,51.3748027778,609.6 -2.784633,51.3755981944,609.6 -2.7852789747,51.3785715963,609.6 -2.785580968,51.3815663965,609.6 -2.7855373333,51.3845670278,609.6 -2.8056222222,51.38377222220001,609.6 -2.8047333333,51.3748027778,609.6 + + + + +
+ + EGRU106C BRISTOL RWY 27 + 512325N 0023807W -
512253N 0023804W -
512251N 0023910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to
512323N 0023913W -
512325N 0023807W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6352888889,51.3904027778,609.6 -2.6535468333,51.389704,609.6 -2.6529092331,51.38672981640001,609.6 -2.6526158735,51.3837346154,609.6 -2.6526682222,51.3807339722,609.6 -2.6343944444,51.3814333333,609.6 -2.6352888889,51.3904027778,609.6 + + + + +
+ + EGRU107A YEOVILTON + 505817N 0024035W thence clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505804N 0023747W -
505817N 0024035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6762913333,50.97146936109999,609.6 -2.6298215278,50.96784299999999,609.6 -2.6239672815,50.96893044029999,609.6 -2.618297061,50.9703547957,609.6 -2.6128593738,50.9721039029,609.6 -2.6077007473,50.974162805,609.6 -2.6028653391,50.97651389319999,609.6 -2.5983945605,50.9791370573,609.6 -2.594326723,50.98200985630001,609.6 -2.5906967097,50.9851077091,609.6 -2.5875356765,50.9884041042,609.6 -2.5848707832,50.991870825,609.6 -2.5827249586,50.9954781906,609.6 -2.581116701,50.99919530889999,609.6 -2.5800599161,51.00299034069999,609.6 -2.5795637937,51.0068307715,609.6 -2.5796327246,51.0106836897,609.6 -2.5802662577,51.01451606890001,609.6 -2.5814590998,51.0182950504,609.6 -2.5832011558,51.0219882257,609.6 -2.5854776109,51.0255639143,609.6 -2.5882690536,51.0289914368,609.6 -2.5915516385,51.0322413781,609.6 -2.5952972881,51.0352858415,609.6 -2.5994739312,51.0380986885,609.6 -2.6040457767,51.0406557648,609.6 -2.60897362,51.0429351086,609.6 -2.6142151797,51.0449171406,609.6 -2.6197254613,51.0465848329,609.6 -2.6254571452,51.0479238563,609.6 -2.6313609955,51.0489227048,609.6 -2.6373862853,51.0495727947,609.6 -2.643481236,51.049868539,609.6 -2.6495934654,51.0498073961,609.6 -2.6556704418,51.0493898914,609.6 -2.6616599388,51.0486196131,609.6 -2.6675104878,51.04750318080001,609.6 -2.6731718236,51.0460501886,609.6 -2.6785953191,51.04427312149999,609.6 -2.6837344058,51.0421872477,609.6 -2.6885449756,51.0398104864,609.6 -2.6929857609,51.0371632529,609.6 -2.6970186893,51.03426828180001,609.6 -2.7006092105,51.0311504313,609.6 -2.7037265914,51.0278364679,609.6 -2.7063441786,51.0243548361,609.6 -2.708439624,51.0207354127,609.6 -2.7099950736,51.01700925039999,609.6 -2.7109973165,51.01320830969999,609.6 -2.7114378947,51.0093651849,609.6 -2.7113131703,51.0055128239,609.6 -2.7106243521,51.00168424579999,609.6 -2.7093774809,50.9979122577,609.6 -2.7075833724,50.994229174,609.6 -2.7052575206,50.9906665399,609.6 -2.7024199611,50.9872548621,609.6 -2.6990950954,50.9840233479,609.6 -2.6953114796,50.9809996566,609.6 -2.6911015776,50.97820966340001,609.6 -2.6865014817,50.97567723939999,609.6 -2.6815506027,50.9734240479,609.6 -2.6762913333,50.97146936109999,609.6 + + + + +
+ + EGRU107B YEOVILTON RWY 04 + 505754N 0024053W -
505814N 0024134W -
505832N 0024111W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505817N 0024035W -
505817N 0024026W -
505754N 0024053W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6813681667,50.9650763611,609.6 -2.6739531389,50.9712873611,609.6 -2.6762913333,50.97146936109999,609.6 -2.6815638587,50.9734295096,609.6 -2.6865262778,50.97568966670001,609.6 -2.6927310556,50.9704911944,609.6 -2.6813681667,50.9650763611,609.6 + + + + +
+ + EGRU107C YEOVILTON RWY 22 + 510310N 0023540W -
510250N 0023459W -
510210N 0023547W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
510232N 0023626W -
510310N 0023540W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5943472222,51.0527433889,609.6 -2.6070863889,51.04211411110001,609.6 -2.6033052479,51.0402731247,609.6 -2.5997455139,51.03826444290001,609.6 -2.5964258333,51.0360986111,609.6 -2.5829642222,51.0473286111,609.6 -2.5943472222,51.0527433889,609.6 + + + + +
+ + EGRU107D YEOVILTON RWY 08 + 505950N 0024354W -
510022N 0024400W -
510028N 0024241W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505956N 0024235W -
505950N 0024354W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7315610556,50.9971264722,609.6 -2.7097279722,50.9988129167,609.6 -2.7106431331,51.0017583572,609.6 -2.7112195574,51.0047377531,609.6 -2.7114541944,51.0077356111,609.6 -2.7332775556,51.0060498889,609.6 -2.7315610556,50.9971264722,609.6 + + + + +
+ + EGRU107E YEOVILTON RWY 26 + 510110N 0023334W -
510038N 0023328W -
510032N 0023446W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
510104N 0023452W -
510110N 0023334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5594051667,51.019364,609.6 -2.5812353056,51.017707,609.6 -2.5803261568,51.0147607937,609.6 -2.5797560879,51.01178091279999,609.6 -2.579528,51.00878286109999,609.6 -2.5576881667,51.0104406111,609.6 -2.5594051667,51.019364,609.6 + + + + +
+ + EGRU108 PORT OF DOVER + 510907N 0012206E thence clockwise by the arc of a circle radius 2.25 NM centred on 510800N 0011900E to
510656N 0011551E -
510907N 0012206E
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Flight permitted by any unmanned aircraft:
operating in the service of the Port of Dover Police;
operating in the service of the Kent Police;
operating in the service of Kent Fire and Rescue Service; or
operating with the permission of the Port of Dover Police.

SI 1329/2019.

Contact: Refer to Statutory Instrument.

]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3683333333,51.1519444444,304.8 1.2641666667,51.1155555556,304.8 1.2672038795,51.1125068064,304.8 1.270605115,51.10961907119999,304.8 1.2744300642,51.1069497853,304.8 1.2786434752,51.1045235011,304.8 1.2832065412,51.1023625326,304.8 1.2880772581,51.1004867505,304.8 1.2932108101,51.098913401,304.8 1.2985599804,51.09765694829999,304.8 1.304075583,51.096728942,304.8 1.309706913,51.09613791200001,304.8 1.3154022092,51.0958892907,304.8 1.3211091266,51.095985363,304.8 1.3267752144,51.096425246,304.8 1.3323483941,51.0972048968,304.8 1.3377774353,51.09831714909999,304.8 1.3430124231,51.0997517792,304.8 1.3480052141,51.1014955989,304.8 1.3527098772,51.1035325759,304.8 1.357083114,51.1058439808,304.8 1.3610846561,51.1084085577,304.8 1.3646776353,51.1112027189,304.8 1.3678289231,51.1142007606,304.8 1.3705094373,51.1173750984,304.8 1.3726944115,51.1206965203,304.8 1.3743636256,51.1241344542,304.8 1.375501596,51.12765724860001,304.8 1.3760977216,51.1312324636,304.8 1.3761463859,51.1348271693,304.8 1.3756470134,51.1384082484,304.8 1.3746040794,51.1419427016,304.8 1.3730270737,51.1453979519,304.8 1.3709304173,51.1487421452,304.8 1.3683333333,51.1519444444,304.8 + + + + +
+ + EGRU109A GLOUCESTERSHIRE + A circle, 2 NM radius, centred at 515339N 0021002W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1672222222,51.92745636330001,609.6 -2.172758683,51.9272797941,609.6 -2.1782363268,51.92675196230001,609.6 -2.1835969655,51.92587847519999,609.6 -2.1887836621,51.9246686117,609.6 -2.1937413388,51.9231352228,609.6 -2.1984173653,51.9212945947,609.6 -2.2027621196,51.91916627469999,609.6 -2.2067295166,51.91677286220001,609.6 -2.2102774978,51.9141397679,609.6 -2.2133684771,51.9112949423,609.6 -2.2159697386,51.9082685781,609.6 -2.2180537808,51.9050927885,609.6 -2.2195986054,51.9018012655,609.6 -2.2205879463,51.8984289213,609.6 -2.2210114378,51.8950115175,609.6 -2.2208647187,51.89158528549999,609.6 -2.2201494737,51.88818654209999,609.6 -2.2188734096,51.8848513047,609.6 -2.2170501689,51.88161490969999,609.6 -2.2146991796,51.8785116391,609.6 -2.2118454455,51.8755743577,609.6 -2.2085192775,51.8728341663,609.6 -2.2047559697,51.8703200735,609.6 -2.2005954239,51.8680586897,609.6 -2.1960817261,51.8660739467,609.6 -2.19126268,51.8643868459,609.6 -2.186189302,51.8630152369,609.6 -2.1809152833,51.8619736299,609.6 -2.1754964243,51.8612730433,609.6 -2.1699900479,51.8609208876,609.6 -2.1644543965,51.8609208876,609.6 -2.1589480201,51.8612730433,609.6 -2.1535291612,51.8619736299,609.6 -2.1482551424,51.8630152369,609.6 -2.1431817645,51.8643868459,609.6 -2.1383627184,51.8660739467,609.6 -2.1338490206,51.8680586897,609.6 -2.1296884748,51.8703200735,609.6 -2.125925167,51.8728341663,609.6 -2.122598999,51.8755743577,609.6 -2.1197452649,51.8785116391,609.6 -2.1173942755,51.88161490969999,609.6 -2.1155710348,51.8848513047,609.6 -2.1142949708,51.88818654209999,609.6 -2.1135797258,51.89158528549999,609.6 -2.1134330067,51.8950115175,609.6 -2.1138564981,51.8984289213,609.6 -2.1148458391,51.9018012655,609.6 -2.1163906636,51.9050927885,609.6 -2.1184747058,51.9082685781,609.6 -2.1210759673,51.9112949423,609.6 -2.1241669467,51.9141397679,609.6 -2.1277149279,51.91677286220001,609.6 -2.1316823249,51.91916627469999,609.6 -2.1360270792,51.9212945947,609.6 -2.1407031056,51.9231352228,609.6 -2.1456607824,51.9246686117,609.6 -2.1508474789,51.92587847519999,609.6 -2.1562081177,51.92675196230001,609.6 -2.1616857614,51.9272797941,609.6 -2.1672222222,51.92745636330001,609.6 + + + + +
+ + EGRU109B GLOUCESTERSHIRE RWY 04 + 515057N 0021212W -
515115N 0021255W -
515204N 0021200W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515148N 0021115W -
515057N 0021212W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2033861111,51.8490638889,609.6 -2.1874931944,51.8633313889,609.6 -2.191914972,51.8645919882,609.6 -2.1961347567,51.8660948525,609.6 -2.200118,51.8678276944,609.6 -2.2153277778,51.8541694444,609.6 -2.2033861111,51.8490638889,609.6 + + + + +
+ + EGRU109C GLOUCESTERSHIRE RWY 22 + 515605N 0020732W -
515547N 0020648W -
515501N 0020740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515521N 0020821W -
515605N 0020732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1254277778,51.93474999999999,609.6 -2.1390743333,51.92254116669999,609.6 -2.1350394219,51.92084952310001,609.6 -2.1312688435,51.9189390143,609.6 -2.1277935278,51.9168253333,609.6 -2.1134611111,51.9296444444,609.6 -2.1254277778,51.93474999999999,609.6 + + + + +
+ + EGRU109D GLOUCESTERSHIRE RWY 04G + 515105N 0021200W -
515123N 0021243W -
515203N 0021158W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515147N 0021112W -
515105N 0021200W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1998861111,51.8513694444,609.6 -2.1867024167,51.86313675,609.6 -2.1911634416,51.8643562518,609.6 -2.1954279461,51.86582079039999,609.6 -2.1994608889,51.8675183611,609.6 -2.2118055556,51.85649722219999,609.6 -2.1998861111,51.8513694444,609.6 + + + + +
+ + EGRU109E GLOUCESTERSHIRE RWY 22G + 515557N 0020735W -
515539N 0020652W -
515459N 0020737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515520N 0020817W -
515557N 0020735W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1264444444,51.9325694444,609.6 -2.13813,51.92217436110001,609.6 -2.1341466733,51.92042848229999,609.6 -2.1304358591,51.9184665182,609.6 -2.1270280833,51.9163046389,609.6 -2.1145027778,51.9274444444,609.6 -2.1264444444,51.9325694444,609.6 + + + + +
+ + EGRU109F GLOUCESTERSHIRE RWY 09 + 515302N 0021455W -
515335N 0021500W -
515342N 0021316W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515310N 0021310W -
515302N 0021455W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.248525,51.8840111111,609.6 -2.2193798056,51.88600116669999,609.6 -2.2203588823,51.8889439051,609.6 -2.2209052777,51.8919292781,609.6 -2.2210144722,51.8949329722,609.6 -2.2501027778,51.8929472222,609.6 -2.248525,51.8840111111,609.6 + + + + +
+ + EGRU109G GLOUCESTERSHIRE RWY 27 + 515414N 0020522W -
515342N 0020517W -
515335N 0020648W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515408N 0020654W -
515414N 0020522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0895777778,51.9038138889,609.6 -2.1149658333,51.9021101667,609.6 -2.1140228124,51.8991634474,609.6 -2.1135131055,51.8961761338,609.6 -2.1134407778,51.8931725556,609.6 -2.0879944444,51.8948805556,609.6 -2.0895777778,51.9038138889,609.6 + + + + +
+ + EGRU110A KEMBLE + A circle, 2 NM radius, centred at 514005N 0020325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0570083333,51.7013520953,609.6 -2.0625171561,51.7011755203,609.6 -2.0679674566,51.7006476712,609.6 -2.0733013381,51.6997741554,609.6 -2.0784621486,51.6985642518,609.6 -2.0833950862,51.6970308118,609.6 -2.0880477837,51.6951901218,609.6 -2.0923708672,51.69306172940001,609.6 -2.0963184816,51.6906682346,609.6 -2.0998487782,51.68803504850001,609.6 -2.1029243581,51.6851901223,609.6 -2.1055126678,51.6821636495,609.6 -2.1075863423,51.67898774419999,609.6 -2.109123492,51.67569609939999,609.6 -2.1101079308,51.67232362830001,609.6 -2.1105293431,51.6689060938,609.6 -2.1103833884,51.6654797288,609.6 -2.1096717414,51.6620808513,609.6 -2.1084020693,51.65874548030001,609.6 -2.1065879451,51.65550895379999,609.6 -2.104248699,51.6524055552,609.6 -2.1014092092,51.6494681512,609.6 -2.0980996349,51.646727844,609.6 -2.0943550938,51.6442136437,609.6 -2.0902152886,51.64195216229999,609.6 -2.0857240857,51.6399673329,609.6 -2.0809290509,51.6382801581,609.6 -2.0758809469,51.6369084885,609.6 -2.0706331981,51.6358668353,609.6 -2.065241328,51.63516621749999,609.6 -2.0597623748,51.6348140461,609.6 -2.0542542919,51.6348140461,609.6 -2.0487753386,51.63516621749999,609.6 -2.0433834685,51.6358668353,609.6 -2.0381357198,51.6369084885,609.6 -2.0330876158,51.6382801581,609.6 -2.028292581,51.6399673329,609.6 -2.0238013781,51.64195216229999,609.6 -2.0196615729,51.6442136437,609.6 -2.0159170318,51.646727844,609.6 -2.0126074574,51.6494681512,609.6 -2.0097679677,51.6524055552,609.6 -2.0074287216,51.65550895379999,609.6 -2.0056145974,51.65874548030001,609.6 -2.0043449253,51.6620808513,609.6 -2.0036332783,51.6654797288,609.6 -2.0034873235,51.6689060938,609.6 -2.0039087359,51.67232362830001,609.6 -2.0048931747,51.67569609939999,609.6 -2.0064303243,51.67898774419999,609.6 -2.0085039989,51.6821636495,609.6 -2.0110923086,51.6851901223,609.6 -2.0141678885,51.68803504850001,609.6 -2.0176981851,51.6906682346,609.6 -2.0216457995,51.69306172940001,609.6 -2.0259688829,51.6951901218,609.6 -2.0306215804,51.6970308118,609.6 -2.035554518,51.6985642518,609.6 -2.0407153286,51.6997741554,609.6 -2.0460492101,51.7006476712,609.6 -2.0514995105,51.7011755203,609.6 -2.0570083333,51.7013520953,609.6 + + + + +
+ + EGRU110B KEMBLE RWY 08 + 513918N 0020819W -
513950N 0020828W -
514001N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
513929N 0020629W -
513918N 0020819W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1386894444,51.6548986944,609.6 -2.1081021667,51.65812861109999,609.6 -2.1093354747,51.6610331599,609.6 -2.1101428888,51.6639950203,609.6 -2.11051775,51.6669900833,609.6 -2.1410953889,51.6637611389,609.6 -2.1386894444,51.6548986944,609.6 + + + + +
+ + EGRU110C KEMBLE RWY 26 + 514052N 0015832W -
514020N 0015823W -
514009N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
514041N 0020021W -
514052N 0015832W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9754756111,51.68114966669999,609.6 -2.0058937778,51.67797455560001,609.6 -2.0046661483,51.675069011,609.6 -2.0038649379,51.672106485,609.6 -2.0034965833,51.66911111110001,609.6 -1.97306875,51.67228725,609.6 -1.9754756111,51.68114966669999,609.6 + + + + +
+ + EGRU110D KEMBLE RWY 08G + 513924N 0020746W -
513956N 0020755W -
514004N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
513932N 0020630W -
513924N 0020746W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1295,51.6566277778,609.6 -2.1084556667,51.65886050000001,609.6 -2.1095817412,51.661782657,609.6 -2.1102796614,51.664756054,609.6 -2.1105436667,51.66775647219999,609.6 -2.1319166667,51.6654888889,609.6 -2.1295,51.6566277778,609.6 + + + + +
+ + EGRU110E KEMBLE RWY 26G + 514053N 0015853W -
514021N 0015844W -
514012N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
514044N 0020023W -
514053N 0015853W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9814111111,51.6813694444,609.6 -2.0063030556,51.6787570556,609.6 -2.0049599261,51.67587043890001,609.6 -2.0040410911,51.6729202744,609.6 -2.0035539444,51.66993061109999,609.6 -1.9789916667,51.6725083333,609.6 -1.9814111111,51.6813694444,609.6 + + + + +
+ + EGRU111A FAIRFORD + A circle, 2.5 NM radius, centred at 514101N 0014724W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7900055556,51.7251302571,609.6 -1.7961881038,51.7249525789,609.6 -1.8023177604,51.7244210644,609.6 -1.80834209,51.72354026050001,609.6 -1.8142095653,51.7223177018,609.6 -1.8198700117,51.7207638457,609.6 -1.8252750386,51.7188919822,609.6 -1.8303784562,51.7167181193,609.6 -1.8351366718,51.7142608454,609.6 -1.8395090636,51.711541169,609.6 -1.8434583283,51.7085823379,609.6 -1.846950799,51.7054096398,609.6 -1.8499567317,51.7020501846,609.6 -1.8524505575,51.6985326718,609.6 -1.8544110975,51.6948871446,609.6 -1.8558217409,51.69114473199999,609.6 -1.8566705822,51.6873373829,609.6 -1.8569505185,51.6834975923,609.6 -1.8566593054,51.679658124,609.6 -1.8557995713,51.6758517307,609.6 -1.8543787901,51.67211087489999,609.6 -1.8524092124,51.66846745240001,609.6 -1.8499077569,51.6649525207,609.6 -1.8468958622,51.6615960349,609.6 -1.8433993005,51.65842659350001,609.6 -1.8394479548,51.6554711955,609.6 -1.8350755629,51.6527550116,609.6 -1.8303194283,51.6503011708,609.6 -1.8252201018,51.6481305646,609.6 -1.8198210368,51.6462616706,609.6 -1.8141682202,51.6447103955,609.6 -1.8083097825,51.64348994150001,609.6 -1.8022955908,51.6426106944,609.6 -1.796176827,51.6420801356,609.6 -1.7900055556,51.6419027797,609.6 -1.7838342841,51.6420801356,609.6 -1.7777155203,51.6426106944,609.6 -1.7717013286,51.64348994150001,609.6 -1.7658428909,51.6447103955,609.6 -1.7601900743,51.6462616706,609.6 -1.7547910093,51.6481305646,609.6 -1.7496916828,51.6503011708,609.6 -1.7449355482,51.6527550116,609.6 -1.7405631563,51.6554711955,609.6 -1.7366118107,51.65842659350001,609.6 -1.7331152489,51.6615960349,609.6 -1.7301033542,51.6649525207,609.6 -1.7276018987,51.66846745240001,609.6 -1.725632321,51.67211087489999,609.6 -1.7242115398,51.6758517307,609.6 -1.7233518057,51.679658124,609.6 -1.7230605927,51.6834975923,609.6 -1.7233405289,51.6873373829,609.6 -1.7241893702,51.69114473199999,609.6 -1.7256000136,51.6948871446,609.6 -1.7275605536,51.6985326718,609.6 -1.7300543794,51.7020501846,609.6 -1.7330603121,51.7054096398,609.6 -1.7365527828,51.7085823379,609.6 -1.7405020475,51.711541169,609.6 -1.7448744393,51.7142608454,609.6 -1.7496326549,51.7167181193,609.6 -1.7547360725,51.7188919822,609.6 -1.7601410994,51.7207638457,609.6 -1.7658015458,51.7223177018,609.6 -1.7716690211,51.72354026050001,609.6 -1.7776933507,51.7244210644,609.6 -1.7838230073,51.7249525789,609.6 -1.7900055556,51.7251302571,609.6 + + + + +
+ + EGRU111B FAIRFORD RWY 09 + 514037N 0015302W -
514110N 0015304W -
514112N 0015124W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to
514039N 0015123W -
514037N 0015302W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8839879444,51.6769958333,609.6 -1.8562672222,51.6776048333,609.6 -1.85678249,51.6805888471,609.6 -1.8569504954,51.68358818580001,609.6 -1.8567703056,51.68658725,609.6 -1.8844827222,51.6859784444,609.6 -1.8839879444,51.6769958333,609.6 + + + + +
+ + EGRU111C FAIRFORD RWY 27 + 514124N 0014146W -
514052N 0014144W -
514050N 0014324W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to
514122N 0014325W -
514124N 0014146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6959973611,51.6899902222,609.6 -1.7237330278,51.6894188889,609.6 -1.7232232057,51.686434517,609.6 -1.7230607719,51.68343506699999,609.6 -1.7232465278,51.6804361389,609.6 -1.6955025278,51.6810076389,609.6 -1.6959973611,51.6899902222,609.6 + + + + +
+ + EGRU112A NETHERAVON + A circle, 2 NM radius, centred at 511453N 0014517W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7548361111,51.28138782650001,609.6 -1.7602945509,51.2812112407,609.6 -1.7656950054,51.2806833593,609.6 -1.7709801093,51.27980978979999,609.6 -1.7760937305,51.2785998114,609.6 -1.7809815694,51.27706627589999,609.6 -1.7855917388,51.2752254703,609.6 -1.7898753167,51.2730969429,609.6 -1.7937868678,51.27070329439999,609.6 -1.7972849255,51.268069937,609.6 -1.8003324321,51.2652248232,609.6 -1.8028971307,51.262198148,609.6 -1.8049519048,51.259022027,609.6 -1.8064750628,51.255730155,609.6 -1.8074505644,51.2523574476,609.6 -1.807868186,51.2489396698,609.6 -1.807723624,51.2455130569,609.6 -1.8070185356,51.2421139298,609.6 -1.8057605153,51.2387783101,609.6 -1.80396301,51.2355415388,609.6 -1.8016451713,51.2324379023,609.6 -1.7988316485,51.2295002701,609.6 -1.7955523241,51.22675974749999,609.6 -1.7918419943,51.2242453475,609.6 -1.7877399989,51.22198368459999,609.6 -1.7832898041,51.2199986946,609.6 -1.7785385418,51.2183113821,609.6 -1.7735365123,51.2169396,609.6 -1.7683366538,51.2158978609,609.6 -1.7629939845,51.2151971852,609.6 -1.7575650239,51.2148449846,609.6 -1.7521071983,51.2148449846,609.6 -1.7466782377,51.2151971852,609.6 -1.7413355684,51.2158978609,609.6 -1.7361357099,51.2169396,609.6 -1.7311336805,51.2183113821,609.6 -1.7263824182,51.2199986946,609.6 -1.7219322233,51.22198368459999,609.6 -1.717830228,51.2242453475,609.6 -1.7141198982,51.22675974749999,609.6 -1.7108405737,51.2295002701,609.6 -1.7080270509,51.2324379023,609.6 -1.7057092122,51.2355415388,609.6 -1.7039117069,51.2387783101,609.6 -1.7026536866,51.2421139298,609.6 -1.7019485982,51.2455130569,609.6 -1.7018040362,51.2489396698,609.6 -1.7022216578,51.2523574476,609.6 -1.7031971595,51.255730155,609.6 -1.7047203175,51.259022027,609.6 -1.7067750915,51.262198148,609.6 -1.7093397901,51.2652248232,609.6 -1.7123872968,51.268069937,609.6 -1.7158853544,51.27070329439999,609.6 -1.7197969055,51.2730969429,609.6 -1.7240804834,51.2752254703,609.6 -1.7286906528,51.27706627589999,609.6 -1.7335784917,51.2785998114,609.6 -1.7386921129,51.27980978979999,609.6 -1.7439772169,51.2806833593,609.6 -1.7493776714,51.2812112407,609.6 -1.7548361111,51.28138782650001,609.6 + + + + +
+ + EGRU112B NETHERAVON RWY 04 + 511235N 0014751W -
511255N 0014830W -
511333N 0014739W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511312N 0014700W -
511235N 0014751W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7974191944,51.2095862778,609.6 -1.7833475,51.22002175,609.6 -1.7872618918,51.22174906989999,609.6 -1.7909127083,51.22369081829999,609.6 -1.7942702222,51.22583122220001,609.6 -1.8083353333,51.2153988056,609.6 -1.7974191944,51.2095862778,609.6 + + + + +
+ + EGRU112C NETHERAVON RWY 22 + 511718N 0014235W -
511657N 0014156W -
511613N 0014255W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511634N 0014335W -
511718N 0014235W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7097918611,51.2883559167,609.6 -1.7262928889,51.2761612222,609.6 -1.7223759775,51.2744320342,609.6 -1.7187238237,51.27248831,609.6 -1.7153661944,51.2703458889,609.6 -1.6988584444,51.2825434722,609.6 -1.7097918611,51.2883559167,609.6 + + + + +
+ + EGRU112D NETHERAVON RWY 11 + 511535N 0014957W -
511605N 0014941W -
511546N 0014809W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511515N 0014825W -
511535N 0014957W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8324731944,51.25960272219999,609.6 -1.8069665833,51.25427375,609.6 -1.8058682165,51.2571979427,609.6 -1.8043540669,51.26004808249999,609.6 -1.8024363889,51.2628009444,609.6 -1.8279352222,51.26812838890001,609.6 -1.8324731944,51.25960272219999,609.6 + + + + +
+ + EGRU112E NETHERAVON RWY 29 + 511412N 0014038W -
511341N 0014054W -
511400N 0014226W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511431N 0014210W -
511412N 0014038W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6772466667,51.2365466389,609.6 -1.7027167778,51.2419014167,609.6 -1.7038199435,51.2389779812,609.6 -1.7053382967,51.23612885570001,609.6 -1.7072593889,51.23337722220001,609.6 -1.6817815278,51.2280209167,609.6 -1.6772466667,51.2365466389,609.6 + + + + +
+ + EGRU113A BOSCOMBE + A circle, 2.5 NM radius, centred at 510912N 0014504W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7510111111,51.194925709,609.6 -1.7571224367,51.1947480177,609.6 -1.7631814827,51.1942164639,609.6 -1.7691364201,51.1933355946,609.6 -1.774936318,51.1921129447,609.6 -1.7805315813,51.1905589717,609.6 -1.7858743789,51.18868696609999,609.6 -1.790919054,51.1865129364,609.6 -1.7956225166,51.1840554715,609.6 -1.799944613,51.1813355807,609.6 -1.8038484688,51.178376513,609.6 -1.8073008037,51.1752035572,609.6 -1.8102722147,51.17184382440001,609.6 -1.812737425,51.1683260161,609.6 -1.814675497,51.16468017710001,609.6 -1.8160700079,51.16093743879999,609.6 -1.8169091861,51.1571297523,609.6 -1.8171860069,51.15328961539999,609.6 -1.8168982483,51.1494497946,609.6 -1.8160485048,51.14564304589999,609.6 -1.8146441607,51.141901835,609.6 -1.8126973227,51.13825806109999,609.6 -1.8102247121,51.1347427851,609.6 -1.8072475184,51.1313859657,609.6 -1.8037912153,51.1282162051,609.6 -1.7998853411,51.1252605058,609.6 -1.7955632448,51.1225440417,609.6 -1.7908618005,51.12008994509999,609.6 -1.7858210936,51.1179191107,609.6 -1.7804840787,51.1160500185,609.6 -1.7748962157,51.1144985778,609.6 -1.7691050838,51.1132779929,609.6 -1.7631599794,51.11239865100001,609.6 -1.7571114989,51.11186803500001,609.6 -1.7510111111,51.1116906599,609.6 -1.7449107234,51.11186803500001,609.6 -1.7388622428,51.11239865100001,609.6 -1.7329171384,51.1132779929,609.6 -1.7271260066,51.1144985778,609.6 -1.7215381435,51.1160500185,609.6 -1.7162011287,51.1179191107,609.6 -1.7111604217,51.12008994509999,609.6 -1.7064589775,51.1225440417,609.6 -1.7021368811,51.1252605058,609.6 -1.6982310069,51.1282162051,609.6 -1.6947747038,51.1313859657,609.6 -1.6917975101,51.1347427851,609.6 -1.6893248995,51.13825806109999,609.6 -1.6873780615,51.141901835,609.6 -1.6859737175,51.14564304589999,609.6 -1.6851239739,51.1494497946,609.6 -1.6848362153,51.15328961539999,609.6 -1.6851130361,51.1571297523,609.6 -1.6859522143,51.16093743879999,609.6 -1.6873467253,51.16468017710001,609.6 -1.6892847972,51.1683260161,609.6 -1.6917500075,51.17184382440001,609.6 -1.6947214185,51.1752035572,609.6 -1.6981737535,51.178376513,609.6 -1.7020776092,51.1813355807,609.6 -1.7063997056,51.1840554715,609.6 -1.7111031682,51.1865129364,609.6 -1.7161478433,51.18868696609999,609.6 -1.7214906409,51.1905589717,609.6 -1.7270859043,51.1921129447,609.6 -1.7328858021,51.1933355946,609.6 -1.7388407396,51.1942164639,609.6 -1.7448997855,51.1947480177,609.6 -1.7510111111,51.194925709,609.6 + + + + +
+ + EGRU113B BOSCOMBE RWY 05 + 510643N 0014908W -
510707N 0014941W -
510749N 0014822W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510724N 0014749W -
510643N 0014908W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8188315556,51.1118148056,609.6 -1.7969201389,51.12334375,609.6 -1.8002337125,51.12550256110001,609.6 -1.8032917451,51.127805952,609.6 -1.8060783056,51.1302419722,609.6 -1.8279827222,51.11871552780001,609.6 -1.8188315556,51.1118148056,609.6 + + + + +
+ + EGRU113C BOSCOMBE RWY 23 + 511139N 0014103W -
511114N 0014030W -
511035N 0014145W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511100N 0014218W -
511139N 0014103W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6841814444,51.19420625,609.6 -1.7050659722,51.1832688889,609.6 -1.7017510046,51.1811084272,609.6 -1.6986927047,51.1788033417,609.6 -1.6959069722,51.1763656389,609.6 -1.6750153333,51.1873056111,609.6 -1.6841814444,51.19420625,609.6 + + + + +
+ + EGRU113D BOSCOMBE RWY 05N + 510706N 0014834W -
510731N 0014907W -
510753N 0014826W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510727N 0014754W -
510706N 0014834W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8093775,51.118341,609.6 -1.7982730833,51.1241878611,609.6 -1.8014879624,51.1264067992,609.6 -1.8044405247,51.1287657571,609.6 -1.8071153889,51.1312524722,609.6 -1.8185353056,51.1252389167,609.6 -1.8093775,51.118341,609.6 + + + + +
+ + EGRU113E BOSCOMBE RWY 23N + 511114N 0014202W -
511049N 0014129W -
511039N 0014149W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511103N 0014223W -
511114N 0014202W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7004613056,51.1872856389,609.6 -1.7065058611,51.1841162222,609.6 -1.7030883915,51.18201788359999,609.6 -1.6999208758,51.179770037,609.6 -1.6970197778,51.1773844167,609.6 -1.6912912222,51.1803878056,609.6 -1.7004613056,51.1872856389,609.6 + + + + +
+ + EGRU113F BOSCOMBE RWY 05S + 510635N 0014909W -
510700N 0014941W -
510745N 0014817W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510720N 0014743W -
510635N 0014909W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8190288333,51.1098363889,609.6 -1.7952359444,51.12235775000001,609.6 -1.7986686484,51.1244440448,609.6 -1.8018536395,51.12668060710001,609.6 -1.8047743333,51.1290558056,609.6 -1.8281826944,51.11673549999999,609.6 -1.8190288333,51.1098363889,609.6 + + + + +
+ + EGRU113H BOSCOMBE RWY 17 + 511215N 0014526W -
511223N 0014436W -
511139N 0014419W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511142N 0014513W -
511215N 0014526W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7572530278,51.20422258329999,609.6 -1.7536991944,51.1948913889,609.6 -1.7486860338,51.1949000253,609.6 -1.7436862295,51.1946701902,609.6 -1.7387285,51.1942031944,609.6 -1.743336,51.2063113333,609.6 -1.7572530278,51.20422258329999,609.6 + + + + +
+ + EGRU113I BOSCOMBE RWY 35 + 510608N 0014214W -
510600N 0014304W -
510656N 0014325W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510713N 0014238W -
510608N 0014214W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7037857778,51.1021631111,609.6 -1.7106696111,51.12032522220001,609.6 -1.7147495861,51.1185007217,609.6 -1.7190368393,51.1168755177,609.6 -1.7235068333,51.1154588889,609.6 -1.7176715,51.10007430560001,609.6 -1.7037857778,51.1021631111,609.6 + + + + +
+ + EGRU114A THRUXTON + A circle, 2 NM radius, centred at 511240N 0013549W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5969805556,51.2445019264,609.6 -1.6024346282,51.2443253397,609.6 -1.6078307621,51.2437974554,609.6 -1.6131116381,51.2429238812,609.6 -1.618221169,51.2417138962,609.6 -1.6231050988,51.24018035229999,609.6 -1.6277115819,51.23833953649999,609.6 -1.6319917356,51.2362109971,609.6 -1.6359001607,51.2338173351,609.6 -1.6393954239,51.2311839626,609.6 -1.6424404972,51.2283388323,609.6 -1.6450031492,51.2253121392,609.6 -1.6470562849,51.2221359992,609.6 -1.6485782301,51.21884410730001,609.6 -1.649552957,51.215471379,609.6 -1.64997025,51.21205357979999,609.6 -1.6498258088,51.2086269452,609.6 -1.6491212888,51.2052277961,609.6 -1.6478642784,51.2018921545,609.6 -1.6460682136,51.1986553617,609.6 -1.6437522304,51.1955517043,609.6 -1.6409409584,51.192614052,609.6 -1.637664256,51.1898735105,609.6 -1.6339568916,51.1873590929,609.6 -1.6298581736,51.1850974141,609.6 -1.6254115333,51.1831124099,609.6 -1.6206640652,51.18142508540001,609.6 -1.6156660294,51.1800532933,609.6 -1.6104703221,51.17901154670001,609.6 -1.6051319175,51.1783108659,609.6 -1.5997072902,51.1779586627,609.6 -1.5942538209,51.1779586627,609.6 -1.5888291937,51.1783108659,609.6 -1.5834907891,51.17901154670001,609.6 -1.5782950817,51.1800532933,609.6 -1.573297046,51.18142508540001,609.6 -1.5685495778,51.1831124099,609.6 -1.5641029375,51.1850974141,609.6 -1.5600042195,51.1873590929,609.6 -1.5562968551,51.1898735105,609.6 -1.5530201527,51.192614052,609.6 -1.5502088807,51.1955517043,609.6 -1.5478928975,51.1986553617,609.6 -1.5460968327,51.2018921545,609.6 -1.5448398223,51.2052277961,609.6 -1.5441353023,51.2086269452,609.6 -1.5439908611,51.21205357979999,609.6 -1.5444081541,51.215471379,609.6 -1.545382881,51.21884410730001,609.6 -1.5469048262,51.2221359992,609.6 -1.5489579619,51.2253121392,609.6 -1.5515206139,51.2283388323,609.6 -1.5545656872,51.2311839626,609.6 -1.5580609505,51.2338173351,609.6 -1.5619693756,51.2362109971,609.6 -1.5662495292,51.23833953649999,609.6 -1.5708560123,51.24018035229999,609.6 -1.5757399421,51.2417138962,609.6 -1.580849473,51.2429238812,609.6 -1.586130349,51.2437974554,609.6 -1.5915264829,51.2443253397,609.6 -1.5969805556,51.2445019264,609.6 + + + + +
+ + EGRU114B THRUXTON RWY 07 + 511117N 0013954W -
511147N 0014014W -
511209N 0013853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511139N 0013833W -
511117N 0013954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6649138889,51.1881222222,609.6 -1.6424814167,51.1941383889,609.6 -1.6447465308,51.19678413369999,609.6 -1.6466230757,51.1995473688,609.6 -1.6480957222,51.2024056111,609.6 -1.6705194444,51.19639166670001,609.6 -1.6649138889,51.1881222222,609.6 + + + + +
+ + EGRU114C THRUXTON RWY 25 + 511403N 0013144W -
511334N 0013124W -
511312N 0013245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511342N 0013305W -
511403N 0013144W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5288583333,51.2342861111,609.6 -1.5514453333,51.22825975,609.6 -1.5491841987,51.2256122627,609.6 -1.5473125872,51.22284753870001,609.6 -1.5458456667,51.21998811109999,609.6 -1.52325,51.2260166667,609.6 -1.5288583333,51.2342861111,609.6 + + + + +
+ + EGRU114D THRUXTON RWY 12 + 511357N 0014004W -
511424N 0013936W -
511354N 0013820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511326N 0013846W -
511357N 0014004W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6677805556,51.23258333330001,609.6 -1.6460598611,51.2237947222,609.6 -1.6440514429,51.2265260821,609.6 -1.6416583054,51.2291324058,609.6 -1.6388999444,51.2315923889,609.6 -1.6600138889,51.2401361111,609.6 -1.6677805556,51.23258333330001,609.6 + + + + +
+ + EGRU114E THRUXTON RWY 30 + 511116N 0013150W -
511048N 0013218W -
511118N 0013331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511144N 0013301W -
511116N 0013150W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5306666667,51.1876861111,609.6 -1.55016125,51.1956079444,609.6 -1.5525946413,51.193017224,609.6 -1.555389954,51.1905750191,609.6 -1.5585243611,51.18830125000001,609.6 -1.5384222222,51.1801333333,609.6 -1.5306666667,51.1876861111,609.6 + + + + +
+ + EGRU115A BRIZE NORTON + A circle, 2.5 NM radius, centred at 514500N 0013459W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5829472222,51.79159922819999,609.6 -1.5891388545,51.7914215516,609.6 -1.5952775171,51.790890042,609.6 -1.6013106972,51.7900092462,609.6 -1.6071867917,51.7887866989,609.6 -1.6128555517,51.7872328574,609.6 -1.6182685155,51.7853610116,609.6 -1.6233794253,51.7831871695,609.6 -1.6281446243,51.7807299195,609.6 -1.632523431,51.7780102697,609.6 -1.6364784872,51.7750514682,609.6 -1.6399760768,51.7718788023,609.6 -1.6429864125,51.7685193817,609.6 -1.6454838879,51.76500190580001,609.6 -1.6474472935,51.7613564176,609.6 -1.6488599943,51.7576140457,609.6 -1.6497100679,51.7538067388,609.6 -1.6499904014,51.7499669915,609.6 -1.6496987476,51.74612756720001,609.6 -1.6488377392,51.7423212184,609.6 -1.6474148615,51.7385804071,609.6 -1.6454423834,51.7349370286,609.6 -1.6429372489,51.7314221399,609.6 -1.6399209283,51.7280656959,609.6 -1.6364192318,51.72489629449999,609.6 -1.6324620865,51.7219409343,609.6 -1.6280832799,51.7192247855,609.6 -1.6233201699,51.7167709767,609.6 -1.618213367,51.71460039919999,609.6 -1.612806388,51.7127315299,609.6 -1.6071452871,51.7111802756,609.6 -1.6012782652,51.7099598381,609.6 -1.595255262,51.7090806028,609.6 -1.5891275342,51.7085500512,609.6 -1.5829472222,51.7083726977,609.6 -1.5767669102,51.7085500512,609.6 -1.5706391824,51.7090806028,609.6 -1.5646161793,51.7099598381,609.6 -1.5587491573,51.7111802756,609.6 -1.5530880564,51.7127315299,609.6 -1.5476810775,51.71460039919999,609.6 -1.5425742745,51.7167709767,609.6 -1.5378111646,51.7192247855,609.6 -1.5334323579,51.7219409343,609.6 -1.5294752127,51.72489629449999,609.6 -1.5259735161,51.7280656959,609.6 -1.5229571956,51.7314221399,609.6 -1.5204520611,51.7349370286,609.6 -1.518479583,51.7385804071,609.6 -1.5170567052,51.7423212184,609.6 -1.5161956968,51.74612756720001,609.6 -1.515904043,51.7499669915,609.6 -1.5161843765,51.7538067388,609.6 -1.5170344501,51.7576140457,609.6 -1.518447151,51.7613564176,609.6 -1.5204105566,51.76500190580001,609.6 -1.522908032,51.7685193817,609.6 -1.5259183676,51.7718788023,609.6 -1.5294159573,51.7750514682,609.6 -1.5333710135,51.7780102697,609.6 -1.5377498201,51.7807299195,609.6 -1.5425150191,51.7831871695,609.6 -1.5476259289,51.7853610116,609.6 -1.5530388928,51.7872328574,609.6 -1.5587076528,51.7887866989,609.6 -1.5645837472,51.7900092462,609.6 -1.5706169273,51.790890042,609.6 -1.5767555899,51.7914215516,609.6 -1.5829472222,51.79159922819999,609.6 + + + + +
+ + EGRU115B BRIZE NORTON RWY 07 + 514344N 0014017W -
514415N 0014032W -
514433N 0013856W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to
514402N 0013841W -
514344N 0014017W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6714538333,51.72900125,609.6 -1.6447841389,51.7339242778,609.6 -1.6464897503,51.736732361,609.6 -1.6478651552,51.7396094469,609.6 -1.6489031389,51.7425405833,609.6 -1.6755641667,51.7376190556,609.6 -1.6714538333,51.72900125,609.6 + + + + +
+ + EGRU115C BRIZE NORTON RWY 25 + 514615N 0012940W -
514544N 0012925W -
514527N 0013101W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to
514558N 0013116W -
514615N 0012940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4943830556,51.77092427780001,609.6 -1.5210811389,51.7660371944,609.6 -1.5193796402,51.7632279118,609.6 -1.5180090481,51.7603498265,609.6 -1.5169764444,51.7574179167,609.6 -1.4902697222,51.7623065278,609.6 -1.4943830556,51.77092427780001,609.6 + + + + +
+ + EGRU116A MIDDLE WALLOP + A circle, 2 NM radius, centred at 510828N 0013422W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5726722222,51.17427732819999,609.6 -1.5781180062,51.1741007397,609.6 -1.5835059398,51.17357285,609.6 -1.5887787912,51.1726992668,609.6 -1.5938805588,51.1714892692,609.6 -1.5987570692,51.1699557093,609.6 -1.6033565558,51.16811487399999,609.6 -1.6076302102,51.165986312,609.6 -1.6115327024,51.1635926242,609.6 -1.6150226618,51.1609592229,609.6 -1.6180631166,51.1581140612,609.6 -1.6206218842,51.15508733410001,609.6 -1.6226719104,51.1519111579,609.6 -1.6241915537,51.14861922789999,609.6 -1.6251648102,51.14524646,609.6 -1.6255814795,51.1418286201,609.6 -1.6254372673,51.1384019438,609.6 -1.6247338262,51.135002753,609.6 -1.6234787327,51.13166706970001,609.6 -1.6216854019,51.12843023589999,609.6 -1.6193729405,51.1253265386,609.6 -1.6165659404,51.12238884820001,609.6 -1.6132942145,51.1196482706,609.6 -1.6095924784,51.1171338196,609.6 -1.6054999807,51.1148721104,609.6 -1.6010600869,51.1128870793,609.6 -1.59631982,51.11119973179999,609.6 -1.5913293643,51.1098279209,609.6 -1.5861415357,51.10878616000001,609.6 -1.5808112254,51.1080854694,609.6 -1.5753948227,51.1077332614,609.6 -1.5699496217,51.1077332614,609.6 -1.564533219,51.1080854694,609.6 -1.5592029088,51.10878616000001,609.6 -1.5540150801,51.1098279209,609.6 -1.5490246244,51.11119973179999,609.6 -1.5442843576,51.1128870793,609.6 -1.5398444637,51.1148721104,609.6 -1.535751966,51.1171338196,609.6 -1.5320502299,51.1196482706,609.6 -1.5287785041,51.12238884820001,609.6 -1.525971504,51.1253265386,609.6 -1.5236590426,51.12843023589999,609.6 -1.5218657117,51.13166706970001,609.6 -1.5206106182,51.135002753,609.6 -1.5199071771,51.1384019438,609.6 -1.5197629649,51.1418286201,609.6 -1.5201796342,51.14524646,609.6 -1.5211528908,51.14861922789999,609.6 -1.522672534,51.1519111579,609.6 -1.5247225603,51.15508733410001,609.6 -1.5272813278,51.1581140612,609.6 -1.5303217826,51.1609592229,609.6 -1.5338117421,51.1635926242,609.6 -1.5377142342,51.165986312,609.6 -1.5419878886,51.16811487399999,609.6 -1.5465873752,51.1699557093,609.6 -1.5514638856,51.1714892692,609.6 -1.5565656532,51.1726992668,609.6 -1.5618385047,51.17357285,609.6 -1.5672264383,51.1741007397,609.6 -1.5726722222,51.17427732819999,609.6 + + + + +
+ + EGRU116B MIDDLE WALLOP RWY 08 + 510812N 0013842W -
510844N 0013847W -
510849N 0013729W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510816N 0013731W -
510812N 0013842W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6450034167,51.1365355833,609.6 -1.6253642222,51.13786924999999,609.6 -1.6255978757,51.140904555,609.6 -1.6253905593,51.14394061749999,609.6 -1.6247439722,51.1469521389,609.6 -1.6465238611,51.14547324999999,609.6 -1.6450034167,51.1365355833,609.6 + + + + +
+ + EGRU116C MIDDLE WALLOP RWY 26 + 510922N 0012924W -
510849N 0012919W -
510842N 0013112W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510914N 0013126W -
510922N 0012924W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4901112778,51.15600175000001,609.6 -1.52378725,51.153753,609.6 -1.5221410871,51.1508959449,609.6 -1.5209162238,51.14795636429999,609.6 -1.5201227222,51.1449587778,609.6 -1.4885904722,51.1470641111,609.6 -1.4901112778,51.15600175000001,609.6 + + + + +
+ + EGRU116D MIDDLE WALLOP RWY 17 + 511125N 0013520W -
511129N 0013429W -
511027N 0013418W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
511024N 0013509W -
511125N 0013520W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.588953,51.19038572219999,609.6 -1.5857961667,51.1732382222,609.6 -1.5811173714,51.1738510424,609.6 -1.5763696609,51.1741960353,609.6 -1.5715917778,51.1742703889,609.6 -1.5747432222,51.1914171111,609.6 -1.588953,51.19038572219999,609.6 + + + + +
+ + EGRU116E MIDDLE WALLOP RWY 35 + 510530N 0013323W -
510526N 0013414W -
510628N 0013426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510631N 0013334W -
510530N 0013323W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.556427,51.0915795,609.6 -1.5595671111,51.1087266944,609.6 -1.5642396379,51.1081147689,609.6 -1.5689806823,51.10777029689999,609.6 -1.5737517222,51.1076960833,609.6 -1.5706061667,51.0905481111,609.6 -1.556427,51.0915795,609.6 + + + + +
+ + EGRU117A OXFORD + A circle, 2 NM radius, centred at 515013N 0011912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.32,51.8702344667,609.6 -1.3255294318,51.870057896,609.6 -1.3310001216,51.8695300599,609.6 -1.3363539553,51.8686565655,609.6 -1.3415340685,51.8674466918,609.6 -1.3464854536,51.86591329000001,609.6 -1.351155547,51.8640726463,609.6 -1.3554947899,51.861944308,609.6 -1.3594571558,51.8595508747,609.6 -1.3630006394,51.85691775719999,609.6 -1.3660877023,51.85407290610001,609.6 -1.3686856699,51.8510465145,609.6 -1.3707670754,51.8478706957,609.6 -1.3723099481,51.8445791419,609.6 -1.3732980424,51.84120676559999,609.6 -1.3737210051,51.8377893287,609.6 -1.3735744804,51.8343630631,609.6 -1.3728601504,51.8309642858,609.6 -1.371585712,51.8276290146,609.6 -1.3697647898,51.8243925863,609.6 -1.3674167871,51.8212892834,609.6 -1.3645666756,51.8183519709,609.6 -1.3612447278,51.8156117502,609.6 -1.3574861927,51.81309763019999,609.6 -1.3533309217,51.8108362217,609.6 -1.3488229448,51.8088514569,609.6 -1.3440100053,51.80716433740001,609.6 -1.3389430551,51.805792713,609.6 -1.3336757173,51.8047510943,609.6 -1.3282637222,51.8040504998,609.6 -1.3227643201,51.8036983402,609.6 -1.3172356799,51.8036983402,609.6 -1.3117362778,51.8040504998,609.6 -1.3063242827,51.8047510943,609.6 -1.3010569449,51.805792713,609.6 -1.2959899947,51.80716433740001,609.6 -1.2911770552,51.8088514569,609.6 -1.2866690783,51.8108362217,609.6 -1.2825138073,51.81309763019999,609.6 -1.2787552722,51.8156117502,609.6 -1.2754333244,51.8183519709,609.6 -1.2725832129,51.8212892834,609.6 -1.2702352102,51.8243925863,609.6 -1.268414288,51.8276290146,609.6 -1.2671398496,51.8309642858,609.6 -1.2664255196,51.8343630631,609.6 -1.2662789949,51.8377893287,609.6 -1.2667019576,51.84120676559999,609.6 -1.2676900519,51.8445791419,609.6 -1.2692329246,51.8478706957,609.6 -1.2713143301,51.8510465145,609.6 -1.2739122977,51.85407290610001,609.6 -1.2769993606,51.85691775719999,609.6 -1.2805428442,51.8595508747,609.6 -1.2845052101,51.861944308,609.6 -1.288844453,51.8640726463,609.6 -1.2935145464,51.86591329000001,609.6 -1.2984659315,51.8674466918,609.6 -1.3036460447,51.8686565655,609.6 -1.3089998784,51.8695300599,609.6 -1.3144705682,51.870057896,609.6 -1.32,51.8702344667,609.6 + + + + +
+ + EGRU117B OXFORD RWY 01 + 514710N 0011941W -
514716N 0012032W -
514819N 0012013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to
514813N 0011922W -
514710N 0011941W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3280333333,51.7861444444,609.6 -1.3226977778,51.80369624999999,609.6 -1.3275216808,51.8039822011,609.6 -1.3322844625,51.8045363966,609.6 -1.3369474167,51.8053543333,609.6 -1.342275,51.78781111109999,609.6 -1.3280333333,51.7861444444,609.6 + + + + +
+ + EGRU117C OXFORD RWY 19 + 515316N 0011843W -
515310N 0011751W -
515207N 0011811W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to
515213N 0011902W -
515316N 0011843W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3118583333,51.8877833333,609.6 -1.3172211389,51.8701899722,609.6 -1.3123911033,51.8698993105,609.6 -1.3076231617,51.8693401192,609.6 -1.3029562222,51.8685169444,609.6 -1.2975861111,51.8861166667,609.6 -1.3118583333,51.8877833333,609.6 + + + + +
+ + EGRU118A BENSON + A circle, 2 NM radius, centred at 513654N 0010545W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0958472222,51.64833017530001,609.6 -1.1013496162,51.648153599,609.6 -1.1067935565,51.64762574589999,609.6 -1.112121214,51.64675222330001,609.6 -1.1172760033,51.6455423103,609.6 -1.1222031865,51.6440088582,609.6 -1.1268504575,51.64216815370001,609.6 -1.1311685001,51.6400397443,609.6 -1.1351115129,51.63764623010001,609.6 -1.1386376959,51.6350130224,609.6 -1.1417096938,51.6321680726,609.6 -1.1442949908,51.62914157429999,609.6 -1.1463662537,51.6259656419,609.6 -1.1479016182,51.62267396840001,609.6 -1.1488849166,51.6193014675,609.6 -1.1493058453,51.6158839024,609.6 -1.1491600683,51.61245750609999,609.6 -1.1484492582,51.6090585972,609.6 -1.1471810729,51.6057231948,609.6 -1.1453690692,51.60248663740001,609.6 -1.1430325547,51.5993832088,609.6 -1.1401963783,51.596445776,609.6 -1.1368906638,51.5937054416,609.6 -1.1331504879,51.5911912162,609.6 -1.1290155071,51.5889297119,609.6 -1.1245295367,51.5869448622,609.6 -1.1197400871,51.58525767,609.6 -1.1146978621,51.58388598620001,609.6 -1.109456224,51.5828443222,609.6 -1.1040706317,51.5821436971,609.6 -1.0985980574,51.581791522,609.6 -1.0930963871,51.581791522,609.6 -1.0876238127,51.5821436971,609.6 -1.0822382205,51.5828443222,609.6 -1.0769965823,51.58388598620001,609.6 -1.0719543573,51.58525767,609.6 -1.0671649077,51.5869448622,609.6 -1.0626789373,51.5889297119,609.6 -1.0585439565,51.5911912162,609.6 -1.0548037807,51.5937054416,609.6 -1.0514980662,51.596445776,609.6 -1.0486618898,51.5993832088,609.6 -1.0463253752,51.60248663740001,609.6 -1.0445133716,51.6057231948,609.6 -1.0432451862,51.6090585972,609.6 -1.0425343761,51.61245750609999,609.6 -1.0423885991,51.6158839024,609.6 -1.0428095278,51.6193014675,609.6 -1.0437928263,51.62267396840001,609.6 -1.0453281907,51.6259656419,609.6 -1.0473994536,51.62914157429999,609.6 -1.0499847507,51.6321680726,609.6 -1.0530567485,51.6350130224,609.6 -1.0565829315,51.63764623010001,609.6 -1.0605259443,51.6400397443,609.6 -1.064843987,51.64216815370001,609.6 -1.069491258,51.6440088582,609.6 -1.0744184411,51.6455423103,609.6 -1.0795732304,51.64675222330001,609.6 -1.084900888,51.64762574589999,609.6 -1.0903448282,51.648153599,609.6 -1.0958472222,51.64833017530001,609.6 + + + + +
+ + EGRU118B BENSON RWY 01 + 513342N 0010601W -
513347N 0010653W -
513459N 0010637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to
513454N 0010545W -
513342N 0010601W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1003111111,51.5617916667,609.6 -1.0959105556,51.5817474444,609.6 -1.100727273,51.5818864152,609.6 -1.1055043408,51.5822951597,609.6 -1.1102029444,51.5829703333,609.6 -1.1145972222,51.5630138889,609.6 -1.1003111111,51.5617916667,609.6 + + + + +
+ + EGRU118C BENSON RWY 19 + 514006N 0010529W -
514001N 0010437W -
513850N 0010453W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to
513854N 0010545W -
514006N 0010529W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0913722222,51.6682888889,609.6 -1.09578375,51.64833013890001,609.6 -1.0909598326,51.6481909345,609.6 -1.0861758008,51.6477815696,609.6 -1.0814706944,51.64710538889999,609.6 -1.0770527778,51.6670638889,609.6 -1.0913722222,51.6682888889,609.6 + + + + +
+ + EGRU119A CHALGROVE + A circle, 2 NM radius, centred at 514028N 0010507W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.08525,51.7078020585,609.6 -1.0907596062,51.7076254837,609.6 -1.0962106817,51.7070976351,609.6 -1.1015453216,51.7062241201,609.6 -1.1067068659,51.7050142177,609.6 -1.1116405047,51.7034807791,609.6 -1.1162938635,51.7016400909,609.6 -1.1206175612,51.69951170059999,609.6 -1.1245657363,51.69711820809999,609.6 -1.1280965342,51.6944850246,609.6 -1.1311725506,51.6916401013,609.6 -1.1337612274,51.6886136316,609.6 -1.1358351958,51.6854377297,609.6 -1.1373725631,51.68214608829999,609.6 -1.1383571408,51.6787736208,609.6 -1.1387786121,51.6753560901,609.6 -1.1386326357,51.67192972880001,609.6 -1.1379208867,51.6685308552,609.6 -1.1366510334,51.66519548800001,609.6 -1.1348366508,51.6619589652,609.6 -1.1324970718,51.6588555703,609.6 -1.1296571783,51.6559181698,609.6 -1.1263471336,51.6531778659,609.6 -1.1226020606,51.6506636687,609.6 -1.1184616675,51.6484021901,609.6 -1.113969827,51.6464173632,609.6 -1.1091741116,51.6447301904,609.6 -1.1041252912,51.6433585225,609.6 -1.0988767978,51.6423168707,609.6 -1.0934841627,51.6416162538,609.6 -1.0880044322,51.6412640828,609.6 -1.0824955678,51.6412640828,609.6 -1.0770158373,51.6416162538,609.6 -1.0716232022,51.6423168707,609.6 -1.0663747088,51.6433585225,609.6 -1.0613258884,51.6447301904,609.6 -1.056530173,51.6464173632,609.6 -1.0520383325,51.6484021901,609.6 -1.0478979394,51.6506636687,609.6 -1.0441528664,51.6531778659,609.6 -1.0408428217,51.6559181698,609.6 -1.0380029282,51.6588555703,609.6 -1.0356633492,51.6619589652,609.6 -1.0338489666,51.66519548800001,609.6 -1.0325791133,51.6685308552,609.6 -1.0318673643,51.67192972880001,609.6 -1.0317213879,51.6753560901,609.6 -1.0321428592,51.6787736208,609.6 -1.0331274369,51.68214608829999,609.6 -1.0346648042,51.6854377297,609.6 -1.0367387726,51.6886136316,609.6 -1.0393274494,51.6916401013,609.6 -1.0424034658,51.6944850246,609.6 -1.0459342637,51.69711820809999,609.6 -1.0498824388,51.69951170059999,609.6 -1.0542061365,51.7016400909,609.6 -1.0588594953,51.7034807791,609.6 -1.0637931341,51.7050142177,609.6 -1.0689546784,51.7062241201,609.6 -1.0742893183,51.7070976351,609.6 -1.0797403938,51.7076254837,609.6 -1.08525,51.7078020585,609.6 + + + + +
+ + EGRU120A ODIHAM + A circle, 2 NM radius, centred at 511403N 0005634W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9428083333,51.2674851282,609.6 -0.948265126,51.2673085421,609.6 -0.9536639509,51.26678065960001,609.6 -0.9589474603,51.2659070883,609.6 -0.9640595387999999,51.2646971075,609.6 -0.9689459033000001,51.26316356880001,609.6 -0.9735546824,51.26132275929999,609.6 -0.9778369687999999,51.2591942274,609.6 -0.9817473409,51.2568005738,609.6 -0.9852443446,51.2541672107,609.6 -0.9882909334999999,51.25132209069999,609.6 -0.9908548602,51.2482954088,609.6 -0.9929090162999999,51.2451192806,609.6 -0.9944317169,51.2418274011,609.6 -0.9954069262999999,51.2384546858,609.6 -0.9958244239999999,51.2350369,609.6 -0.9956799076000001,51.2316102789,609.6 -0.9949750335000001,51.2282111435,609.6 -0.9937173942,51.2248755156,609.6 -0.9919204321000001,51.2216387361,609.6 -0.9896032933000001,51.2185350918,609.6 -0.9867906194,51.215597452,609.6 -0.9835122839,51.2128569223,609.6 -0.9798030725,51.2103425156,609.6 -0.9757023133000001,51.2080808467,609.6 -0.971253459,51.20609585139999,609.6 -0.9665036277,51.2044085344,609.6 -0.9615031045,51.20303674849999,609.6 -0.9563048117,51.2019950066,609.6 -0.9509637509,51.2012943289,609.6 -0.9455364246,51.2009421274,609.6 -0.9400802421,51.2009421274,609.6 -0.9346529158000001,51.2012943289,609.6 -0.929311855,51.2019950066,609.6 -0.9241135621,51.20303674849999,609.6 -0.919113039,51.2044085344,609.6 -0.9143632076,51.20609585139999,609.6 -0.9099143534,51.2080808467,609.6 -0.9058135942,51.2103425156,609.6 -0.9021043827999999,51.2128569223,609.6 -0.8988260472999999,51.215597452,609.6 -0.8960133734,51.2185350918,609.6 -0.8936962345,51.2216387361,609.6 -0.8918992724999999,51.2248755156,609.6 -0.8906416331,51.2282111435,609.6 -0.8899367591,51.2316102789,609.6 -0.8897922427,51.2350369,609.6 -0.8902097403,51.2384546858,609.6 -0.8911849498,51.2418274011,609.6 -0.8927076503,51.2451192806,609.6 -0.8947618064999999,51.2482954088,609.6 -0.8973257331999999,51.25132209069999,609.6 -0.9003723221,51.2541672107,609.6 -0.9038693257999999,51.2568005738,609.6 -0.9077796979,51.2591942274,609.6 -0.9120619843,51.26132275929999,609.6 -0.9166707633,51.26316356880001,609.6 -0.9215571279,51.2646971075,609.6 -0.9266692064000001,51.2659070883,609.6 -0.9319527157,51.26678065960001,609.6 -0.9373515406999999,51.2673085421,609.6 -0.9428083333,51.2674851282,609.6 + + + + +
+ + EGRU120B ODIHAM RWY 09 + 511356N 0010140W -
511428N 0010137W -
511425N 0005942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to
511352N 0005944W -
511356N 0010140W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0277194444,51.2320944444,609.6 -0.9956238056,51.2311932778,609.6 -0.9958410277999998,51.23419482010001,609.6 -0.9956263240999998,51.2371964328,609.6 -0.9949813611000001,51.2401736667,609.6 -1.0270638889,51.241075,609.6 -1.0277194444,51.2320944444,609.6 + + + + +
+ + EGRU120C ODIHAM RWY 27 + 511410N 0005128W -
511338N 0005130W -
511341N 0005326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to
511414N 0005324W -
511410N 0005128W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8577777777999999,51.2362194444,609.6 -0.8899854444,51.2371621944,609.6 -0.889775671,51.2341610401,609.6 -0.8899976551,51.2311602307,609.6 -0.8906495,51.22818419439999,609.6 -0.8584305555999999,51.2272416667,609.6 -0.8577777777999999,51.2362194444,609.6 + + + + +
+ + EGRU121A BLACKBUSHE + 511738N 0005215W thence clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
511806N 0004829W -
511801N 0004919W -
511758N 0004954W -
511753N 0005038W -
511746N 0005120W -
511738N 0005215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8707499999999999,51.29395277780001,609.6 -0.8556861111000001,51.2962277778,609.6 -0.8438138889,51.29795,609.6 -0.8316222222,51.2993666667,609.6 -0.8219555556,51.3003611111,609.6 -0.8080277778,51.30159722220001,609.6 -0.8046211679,51.30423142349999,609.6 -0.8016523744000001,51.3070659151,609.6 -0.7991585751,51.3100749158,609.6 -0.7971657046,51.3132272484,609.6 -0.7956945203999999,51.3164902437,609.6 -0.7947603841999999,51.319830079,609.6 -0.7943730988,51.3232121275,609.6 -0.7945368009,51.3266013175,609.6 -0.7952499138,51.3299624951,609.6 -0.7965051585,51.3332607896,609.6 -0.7982896245,51.33646197549999,609.6 -0.8005848991000001,51.3395328276,609.6 -0.8033672544,51.3424414674,609.6 -0.8066078902000001,51.3451576942,609.6 -0.8102732304000001,51.3476533001,609.6 -0.8143252696,51.349902364,609.6 -0.8187219672000001,51.35188152210001,609.6 -0.8234176835000001,51.3535702113,609.6 -0.8283636551000001,51.3549508846,609.6 -0.833508503,51.35600919419999,609.6 -0.8387987690000001,51.35673414120001,609.6 -0.8441794738000001,51.3571181909,609.6 -0.8495946925,51.3571573517,609.6 -0.8549881386,51.3568512164,609.6 -0.8603037539999999,51.3562029671,609.6 -0.8654862942,51.3552193412,609.6 -0.8704819069,51.3539105616,609.6 -0.875238694,51.3522902294,609.6 -0.879707254,51.3503751817,609.6 -0.8838411967000001,51.34818531580001,609.6 -0.8875976263000002,51.34574338159999,609.6 -0.8909375871,51.3430747435,609.6 -0.8938264674000002,51.3402071163,609.6 -0.8962343572,51.33717027599999,609.6 -0.8981363562,51.3339957498,609.6 -0.8995128292,51.3307164872,609.6 -0.9003496056,51.3273665183,609.6 -0.9006381221999999,51.3239805991,609.6 -0.9003755074000002,51.3205938511,609.6 -0.8995646057,51.3172413967,609.6 -0.8982139433,51.3139579952,609.6 -0.8963376347000002,51.3107776825,609.6 -0.8939552325000001,51.307733419,609.6 -0.8910915201000001,51.30485674889999,609.6 -0.887776252,51.30217747420001,609.6 -0.8840438430999999,51.29972334679999,609.6 -0.8799330102,51.2975197822,609.6 -0.8754863704,51.2955895979,609.6 -0.8707499999999999,51.29395277780001,609.6 + + + + +
+ + EGRU121B BLACKBUSHE RWY 07 + 511815N 0005513W -
511845N 0005530W -
511904N 0005359W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
511834N 0005343W -
511815N 0005513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9204,51.30406388889999,609.6 -0.8952721667000001,51.3093216389,609.6 -0.8971743106000001,51.3120790247,609.6 -0.8986723185,51.31493262669999,609.6 -0.8997539444,51.3178592222,609.6 -0.9249277778,51.3125916667,609.6 -0.9204,51.30406388889999,609.6 + + + + +
+ + EGRU121C BLACKBUSHE RWY 25 + 512038N 0004631W -
512007N 0004614W -
511949N 0004743W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
512019N 0004800W -
512038N 0004631W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7751972222000001,51.343825,609.6 -0.7998953611,51.3386891667,609.6 -0.7979607589,51.33594023149999,609.6 -0.7964298273,51.3330932315,609.6 -0.7953149722,51.3301713611,609.6 -0.7706638889,51.3352972222,609.6 -0.7751972222000001,51.343825,609.6 + + + + +
+ + EGRU122A WYCOMBE AIR PARK/BOOKER + A circle, 2 NM radius, centred at 513642N 0004830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8082305556,51.64502186089999,609.6 -0.8137325491000001,51.64484528449999,609.6 -0.8191760930999999,51.6443174311,609.6 -0.824503363,51.6434439081,609.6 -0.8296577772,51.6422339944,609.6 -0.8345846018999999,51.6407005416,609.6 -0.8392315348,51.6388598362,609.6 -0.8435492635,51.63673142580001,609.6 -0.8474919895999999,51.6343379104,609.6 -0.8510179164,51.6317047013,609.6 -0.8540896911,51.62885975,609.6 -0.8566748005000001,51.6258332502,609.6 -0.8587459132,51.62265731599999,609.6 -0.8602811664000001,51.6193656408,609.6 -0.8612643938000001,51.615993138,609.6 -0.8616852924000001,51.612575571,609.6 -0.8615395265,51.6091491728,609.6 -0.8608287685000001,51.6057502619,609.6 -0.8595606757000001,51.6024148575,609.6 -0.8577488041999999,51.5991782982,609.6 -0.8554124598,51.5960748678,609.6 -0.8525764897999999,51.5931374331,609.6 -0.8492710157,51.590397097,609.6 -0.8455311117999998,51.58788287,609.6 -0.8413964315,51.58562136430001,609.6 -0.8369107871,51.5836365134,609.6 -0.8321216853999999,51.58194932009999,609.6 -0.8270798266,51.58057763539999,609.6 -0.8218385692,51.57953597069999,609.6 -0.816453368,51.5788353451,609.6 -0.8109811909999999,51.57848316979999,609.6 -0.8054799201,51.57848316979999,609.6 -0.8000077430999999,51.5788353451,609.6 -0.7946225419999999,51.57953597069999,609.6 -0.7893812845,51.58057763539999,609.6 -0.7843394257,51.58194932009999,609.6 -0.7795503240000001,51.5836365134,609.6 -0.7750646795999999,51.58562136430001,609.6 -0.7709299992999999,51.58788287,609.6 -0.7671900954,51.590397097,609.6 -0.7638846213,51.5931374331,609.6 -0.7610486513,51.5960748678,609.6 -0.7587123069,51.5991782982,609.6 -0.7569004354000001,51.6024148575,609.6 -0.7556323426,51.6057502619,609.6 -0.7549215847000001,51.6091491728,609.6 -0.7547758187,51.612575571,609.6 -0.7551967173,51.615993138,609.6 -0.7561799447000001,51.6193656408,609.6 -0.7577151979999999,51.62265731599999,609.6 -0.7597863106,51.6258332502,609.6 -0.76237142,51.62885975,609.6 -0.7654431947,51.6317047013,609.6 -0.7689691215,51.6343379104,609.6 -0.7729118476,51.63673142580001,609.6 -0.7772295762999999,51.6388598362,609.6 -0.7818765092999999,51.6407005416,609.6 -0.7868033339,51.6422339944,609.6 -0.7919577480999999,51.6434439081,609.6 -0.797285018,51.6443174311,609.6 -0.802728562,51.64484528449999,609.6 -0.8082305556,51.64502186089999,609.6 + + + + +
+ + EGRU122B WYCOMBE AIR PARK/BOOKER RWY 06 + 513508N 0005225W -
513536N 0005249W -
513602N 0005131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513533N 0005107W -
513508N 0005225W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8734888889,51.58541944440001,609.6 -0.8518406944,51.5924746389,609.6 -0.8544514271,51.5950007053,609.6 -0.8566861956,51.59766302599999,609.6 -0.85852675,51.6004399444,609.6 -0.8801694444,51.5933861111,609.6 -0.8734888889,51.58541944440001,609.6 + + + + +
+ + EGRU122C WYCOMBE AIR PARK/BOOKER RWY 24 + 513817N 0004434W -
513748N 0004410W -
513723N 0004529W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513752N 0004553W -
513817N 0004434W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7428694443999999,51.63803055559999,609.6 -0.7645970833,51.63098213890001,609.6 -0.7619873992000001,51.6284546928,609.6 -0.7597547123,51.6257910769,609.6 -0.7579171667,51.623013,609.6 -0.7361805556000001,51.6300638889,609.6 -0.7428694443999999,51.63803055559999,609.6 + + + + +
+ + EGRU122D WYCOMBE AIR PARK/BOOKER RWY 06G + 513506N 0005218W -
513535N 0005242W -
513559N 0005129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513531N 0005104W -
513506N 0005218W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8717527777999999,51.58513333329999,609.6 -0.8511163333,51.591854,609.6 -0.8538205929,51.5943427601,609.6 -0.8561537856000001,51.5969732224,609.6 -0.8580968611000001,51.5997239722,609.6 -0.8784277778,51.5931027778,609.6 -0.8717527777999999,51.58513333329999,609.6 + + + + +
+ + EGRU122E WYCOMBE AIR PARK/BOOKER RWY 24G + 513814N 0004433W -
513746N 0004408W -
513720N 0004527W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513749N 0004550W -
513814N 0004433W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7423638889,51.6373111111,609.6 -0.7638803889,51.6303364444,609.6 -0.7613668981000001,51.62777105100001,609.6 -0.7592355649,51.6250750191,609.6 -0.7575036944,51.6222703333,609.6 -0.7356805556,51.6293444444,609.6 -0.7423638889,51.6373111111,609.6 + + + + +
+ + EGRU122G WYCOMBE AIR PARK/BOOKER RWY 35 + 513351N 0004703W -
513344N 0004754W -
513443N 0004815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513450N 0004724W -
513351N 0004703W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7843015278,51.5641660833,609.6 -0.7899565833000001,51.58044494439999,609.6 -0.7945577485999999,51.5795466346,609.6 -0.7992699984,51.5789101889,609.6 -0.8040550556,51.5785408056,609.6 -0.798395,51.562262,609.6 -0.7843015278,51.5641660833,609.6 + + + + +
+ + EGRU123A FARNBOROUGH + 511758N 0004954W -
511801N 0004919W -
511806N 0004829W -
511812N 0004723W -
511817N 0004705W -
511851N 0004551W -
511856N 0004537W thence clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to -
511758N 0004954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8316222222,51.2993666667,609.6 -0.8349233580999998,51.2961419297,609.6 -0.8377383331,51.2927409314,609.6 -0.8400421018999999,51.2891919749,609.6 -0.8418152365,51.2855251742,609.6 -0.8430428226,51.2817716363,609.6 -0.843714583,51.2779631961,609.6 -0.8438249598000001,51.2741321464,609.6 -0.8433731571,51.2703109638,609.6 -0.842363143,51.2665320331,609.6 -0.8408036111,51.2628273734,609.6 -0.8387079028,51.2592283667,609.6 -0.8360938895,51.2557654929,609.6 -0.8329838181,51.2524680725,609.6 -0.8294041189999999,51.2493640189,609.6 -0.8253851800999999,51.2464796031,609.6 -0.8209610875,51.2438392327,609.6 -0.8161693361,51.24146524609999,609.6 -0.8110505121,51.2393777248,609.6 -0.8056479499,51.2375943248,609.6 -0.8000073667000001,51.2361301276,609.6 -0.7941764778,51.23499751429999,609.6 -0.7882045952,51.23420606129999,609.6 -0.7821422136,51.23376246,609.6 -0.7760405870000001,51.23367046079999,609.6 -0.7699512981,51.2339308414,609.6 -0.7639258263000001,51.23454140050001,609.6 -0.758015116,51.23549697630001,609.6 -0.7522691488,51.2367894894,609.6 -0.7467365243,51.238408011,609.6 -0.7414640514999999,51.2403388547,609.6 -0.7364963554,51.2425656908,609.6 -0.7318755007,51.2450696839,609.6 -0.7276406369,51.2478296513,609.6 -0.7238276671,51.2508222408,609.6 -0.7204689437,51.25402212709999,609.6 -0.7175929929,51.2574022255,609.6 -0.7152242708999998,51.2609339197,609.6 -0.7133829545,51.2645873035,609.6 -0.7120847663999998,51.2683314329,609.6 -0.7113408381000002,51.2721345878,609.6 -0.7111576111000001,51.2759645403,609.6 -0.7115367784,51.2797888272,609.6 -0.7124752643999999,51.2835750257,609.6 -0.7139652472,51.2872910278,609.6 -0.7159942199,51.290905313,609.6 -0.7185450923999999,51.2943872168,609.6 -0.7215963328999999,51.29770719070001,609.6 -0.725122147,51.3008370544,609.6 -0.729092694,51.3037502357,609.6 -0.7334743386,51.3064219971,609.6 -0.7382299347,51.3088296472,609.6 -0.7433191407,51.3109527342,609.6 -0.7486987625999999,51.3127732211,609.6 -0.7543231217,51.3142756395,609.6 -0.7601444444,51.3154472222,609.6 -0.7641027777999999,51.3140444444,609.6 -0.7846027778,51.30463888890001,609.6 -0.7897027778,51.3033833333,609.6 -0.8080277778,51.30159722220001,609.6 -0.8219555556,51.3003611111,609.6 -0.8316222222,51.2993666667,609.6 + + + + +
+ + EGRU123B FARNBOROUGH RWY 06 + 511452N 0005042W -
511521N 0005107W -
511536N 0005021W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to
511507N 0004957W -
511452N 0005042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8450972222000001,51.24775833330001,609.6 -0.8324629166999999,51.25197830559999,609.6 -0.8349976079,51.2545235792,609.6 -0.8372336199,51.2571768339,609.6 -0.8391593056,51.2599242778,609.6 -0.8518138889,51.2556972222,609.6 -0.8450972222000001,51.24775833330001,609.6 + + + + +
+ + EGRU123C FARNBOROUGH RWY 24 + 511811N 0004233W -
511743N 0004209W -
511727N 0004257W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to
511755N 0004322W -
511811N 0004233W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.709275,51.3031861111,609.6 -0.7226773611000001,51.2987325,609.6 -0.7201248588999999,51.2961928717,609.6 -0.717871246,51.2935444601,609.6 -0.7159282222,51.2908010556,609.6 -0.7025472222,51.2952472222,609.6 -0.709275,51.3031861111,609.6 + + + + +
+ + EGRU124A WHITE WALTHAM + A circle, 2 NM radius, centred at 513002N 0004629W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7748333333,51.53395027229999,609.6 -0.7803219262,51.5337736931,609.6 -0.7857522123,51.5332458312,609.6 -0.7910665085,51.532372294,609.6 -0.7962083715,51.53116236060001,609.6 -0.801123201,51.5296288826,609.6 -0.8057588225,51.5277881466,609.6 -0.8100660436,51.5256597005,609.6 -0.8139991778,51.5232661445,609.6 -0.8175165298000001,51.52063289029999,609.6 -0.8205808377,51.5177878894,609.6 -0.8231596670999999,51.5147613361,609.6 -0.8252257528000001,51.5115853449,609.6 -0.8267572846,51.5082936097,609.6 -0.827738135,51.5049210445,609.6 -0.8281580254000001,51.5015034131,609.6 -0.8280126299,51.49807694940001,609.6 -0.8273036164000001,51.4946779725,609.6 -0.8260386228,51.4913425024,609.6 -0.8242311716,51.4881058784,609.6 -0.821900521,51.4850023851,609.6 -0.8190714576,51.48206489010001,609.6 -0.8157740292999999,51.4793244971,609.6 -0.8120432247,51.4768102173,609.6 -0.807918601,51.4745486636,609.6 -0.8034438637,51.47256377010001,609.6 -0.7986664044,51.4708765405,609.6 -0.7936368002999998,51.469504826,609.6 -0.7884082803999999,51.4684631386,609.6 -0.7830361654,51.4677624977,609.6 -0.7775772851,51.4674103147,609.6 -0.7720893814999999,51.4674103147,609.6 -0.7666305013,51.4677624977,609.6 -0.7612583862999999,51.4684631386,609.6 -0.7560298663999999,51.469504826,609.6 -0.7510002622999999,51.4708765405,609.6 -0.746222803,51.47256377010001,609.6 -0.7417480657,51.4745486636,609.6 -0.7376234419,51.4768102173,609.6 -0.7338926373999999,51.4793244971,609.6 -0.7305952091,51.48206489010001,609.6 -0.7277661456,51.4850023851,609.6 -0.7254354951000002,51.4881058784,609.6 -0.7236280438,51.4913425024,609.6 -0.7223630502,51.4946779725,609.6 -0.7216540366999999,51.49807694940001,609.6 -0.7215086413000001,51.5015034131,609.6 -0.7219285317,51.5049210445,609.6 -0.7229093821,51.5082936097,609.6 -0.7244409138999999,51.5115853449,609.6 -0.7265069995000001,51.5147613361,609.6 -0.729085829,51.5177878894,609.6 -0.7321501369,51.52063289029999,609.6 -0.7356674889,51.5232661445,609.6 -0.7396006231,51.5256597005,609.6 -0.7439078442,51.5277881466,609.6 -0.7485434657000001,51.5296288826,609.6 -0.7534582952,51.53116236060001,609.6 -0.7586001581000001,51.532372294,609.6 -0.7639144543,51.5332458312,609.6 -0.7693447405000001,51.5337736931,609.6 -0.7748333333,51.53395027229999,609.6 + + + + +
+ + EGRU124B WHITE WALTHAM RWY 03 + 512712N 0004802W -
512727N 0004848W -
512819N 0004807W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512807N 0004719W -
512712N 0004802W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8004888889,51.4534388889,609.6 -0.7886194722000001,51.4684981389,609.6 -0.7932141706999999,51.4694066717,609.6 -0.7976589203,51.4705705112,609.6 -0.8019174443999999,51.4719801667,609.6 -0.8133944444,51.4574138889,609.6 -0.8004888889,51.4534388889,609.6 + + + + +
+ + EGRU124C WHITE WALTHAM RWY 21 + 513247N 0004436W -
513233N 0004349W -
513137N 0004433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513154N 0004518W -
513247N 0004436W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7432027778,51.5463361111,609.6 -0.7549029443999999,51.5315407778,609.6 -0.7505130261,51.5302910944,609.6 -0.746322272,51.5287990749,609.6 -0.7423649722,51.52707694440001,609.6 -0.7302722222,51.54236388889999,609.6 -0.7432027778,51.5463361111,609.6 + + + + +
+ + EGRU124D WHITE WALTHAM RWY 07 + 512831N 0005037W -
512900N 0005059W -
512926N 0004932W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512857N 0004910W -
512831N 0005037W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8435944444000001,51.4752861111,609.6 -0.8194776388999999,51.482447,609.6 -0.8219270335,51.4850334633,609.6 -0.8239931833,51.4877472443,609.6 -0.8256592222,51.49056625,609.6 -0.8497666667,51.4834083333,609.6 -0.8435944444000001,51.4752861111,609.6 + + + + +
+ + EGRU124E WHITE WALTHAM RWY 25 + 513134N 0004222W -
513104N 0004159W -
513039N 0004326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513108N 0004349W -
513134N 0004222W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7060083333,51.52598611110001,609.6 -0.7301535555999999,51.51885275,609.6 -0.7277079881000001,51.51626487040001,609.6 -0.7256465230999999,51.5135499515,609.6 -0.7239859167,51.5107301111,609.6 -0.6998305556,51.5178666667,609.6 -0.7060083333,51.52598611110001,609.6 + + + + +
+ + EGRU124F WHITE WALTHAM RWY 11 + 513039N 0005100W -
513109N 0005042W -
513052N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513020N 0004939W -
513039N 0005100W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8499277778000001,51.51070833329999,609.6 -0.8275694999999998,51.5056710833,609.6 -0.8266300624,51.50862355649999,609.6 -0.8252669632,51.5115109942,609.6 -0.8234912778,51.5143097778,609.6 -0.8450222222,51.51916111109999,609.6 -0.8499277778000001,51.51070833329999,609.6 + + + + +
+ + EGRU124G WHITE WALTHAM RWY 29 + 512909N 0004152W -
512839N 0004210W -
512900N 0004345W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512930N 0004324W -
512909N 0004152W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6978833333,51.4859083333,609.6 -0.7234618056,51.49170572220001,609.6 -0.724968234,51.4888470135,609.6 -0.7268817969,51.48608487589999,609.6 -0.7291868056,51.4834418611,609.6 -0.7027833333,51.4774583333,609.6 -0.6978833333,51.4859083333,609.6 + + + + +
+ + EGRU125A HALTON + A circle, 2 NM radius, centred at 514732N 0004411W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.73645,51.8255736098,609.6 -0.7419739621,51.825397038,609.6 -0.7474392404,51.8248691985,609.6 -0.7527877787000001,51.8239956984,609.6 -0.7579627689000001,51.8227858168,609.6 -0.7629092579,51.8212524049,609.6 -0.7675747342999999,51.819411749,609.6 -0.7719096884999999,51.8172833964,609.6 -0.7758681392,51.8148899469,609.6 -0.7794081229000001,51.8122568112,609.6 -0.7824921382000001,51.8094119403,609.6 -0.7850875426,51.8063855272,609.6 -0.7871668962,51.80320968560001,609.6 -0.78870825,51.7999181077,609.6 -0.7896953741,51.79654570630001,609.6 -0.7901179254,51.7931282437,609.6 -0.789971552,51.7897019518,609.6 -0.7892579341,51.786303148,609.6 -0.7879847607,51.7829678504,609.6 -0.7861656427,51.7797313962,609.6 -0.7838199640999999,51.77662806789999,609.6 -0.7809726717,51.77369073130001,609.6 -0.7776540078,51.77095048769999,609.6 -0.7738991868,51.7684363465,609.6 -0.7697480205000001,51.7661749187,609.6 -0.7652444955,51.76419013690001,609.6 -0.7604363079999998,51.76250300269999,609.6 -0.7553743596,51.76113136639999,609.6 -0.7501122209,51.7600897386,609.6 -0.744705567,51.7593891379,609.6 -0.7392115921,51.75903697510001,609.6 -0.7336884078999999,51.75903697510001,609.6 -0.728194433,51.7593891379,609.6 -0.7227877791,51.7600897386,609.6 -0.7175256403999999,51.76113136639999,609.6 -0.712463692,51.76250300269999,609.6 -0.7076555045,51.76419013690001,609.6 -0.7031519795,51.7661749187,609.6 -0.6990008132,51.7684363465,609.6 -0.6952459922000001,51.77095048769999,609.6 -0.6919273283,51.77369073130001,609.6 -0.6890800359,51.77662806789999,609.6 -0.6867343573,51.7797313962,609.6 -0.6849152393,51.7829678504,609.6 -0.6836420659,51.786303148,609.6 -0.682928448,51.7897019518,609.6 -0.6827820746,51.7931282437,609.6 -0.6832046259,51.79654570630001,609.6 -0.68419175,51.7999181077,609.6 -0.6857331038,51.80320968560001,609.6 -0.6878124574,51.8063855272,609.6 -0.6904078618,51.8094119403,609.6 -0.6934918771,51.8122568112,609.6 -0.6970318608,51.8148899469,609.6 -0.7009903115,51.8172833964,609.6 -0.7053252657,51.819411749,609.6 -0.7099907421,51.8212524049,609.6 -0.7149372311000001,51.8227858168,609.6 -0.7201122213,51.8239956984,609.6 -0.7254607596,51.8248691985,609.6 -0.7309260378999999,51.825397038,609.6 -0.73645,51.8255736098,609.6 + + + + +
+ + EGRU125B HALTON RWY 02 + 514440N 0004521W -
514451N 0004610W -
514546N 0004539W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514535N 0004450W -
514440N 0004521W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7558487222,51.7445320556,609.6 -0.7472673332999999,51.7596761944,609.6 -0.7519601648000002,51.76041354200001,609.6 -0.7565269625,51.7614102361,609.6 -0.7609306111,51.76265816669999,609.6 -0.7695065,51.7475157222,609.6 -0.7558487222,51.7445320556,609.6 + + + + +
+ + EGRU125C HALTON RWY 20 + 515024N 0004301W -
515013N 0004212W -
514919N 0004243W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514930N 0004332W -
515024N 0004301W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7170164999999999,51.8400288889,609.6 -0.7256216944,51.8248898889,609.6 -0.7209224785000001,51.82415175580001,609.6 -0.7163499724000001,51.8231539352,609.6 -0.7119414722,51.8219045833,609.6 -0.7033307222,51.83704525,609.6 -0.7170164999999999,51.8400288889,609.6 + + + + +
+ + EGRU125D HALTON RWY 07 + 514615N 0004829W -
514646N 0004846W -
514705N 0004719W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514635N 0004701W -
514615N 0004829W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8080578056,51.7708836389,609.6 -0.78350425,51.7762662222,609.6 -0.7856425451,51.7789628325,609.6 -0.7873803361,51.781768038,609.6 -0.7887033889,51.784659,609.6 -0.8128740833000001,51.77936019440001,609.6 -0.8080578056,51.7708836389,609.6 + + + + +
+ + EGRU125E HALTON RWY 25 + 514840N 0004002W -
514810N 0003944W -
514753N 0004101W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514824N 0004117W -
514840N 0004002W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6671238889,51.8112181389,609.6 -0.6880245278,51.8066635556,609.6 -0.6861315652,51.803896992,609.6 -0.6846489466,51.8010358551,609.6 -0.6835886944,51.7981034722,609.6 -0.6623042222,51.8027416389,609.6 -0.6671238889,51.8112181389,609.6 + + + + +
+ + EGRU126A FAIROAKS + A circle, 2 NM radius, centred at 512053N 0003331W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5587083333,51.3813205885,609.6 -0.5641786514,51.3811440053,609.6 -0.5695908575999999,51.3806161316,609.6 -0.5748874614,51.37974257490001,609.6 -0.580012208,51.3785326144,609.6 -0.5849106794,51.3769991016,609.6 -0.5895308752,51.3751583236,609.6 -0.5938237669999999,51.37302982840001,609.6 -0.5977438204,51.3706362166,609.6 -0.6012494788,51.3680029,609.6 -0.604303604,51.3651578309,609.6 -0.6068738693,51.36213120399999,609.6 -0.6089330994,51.3589551344,609.6 -0.6104595561,51.3556633166,609.6 -0.6114371648,51.35229066549999,609.6 -0.6118556802,51.34887294570001,609.6 -0.6117107899999999,51.3454463918,609.6 -0.6110041553,51.3420473242,609.6 -0.6097433881,51.33871176369999,609.6 -0.6079419646999999,51.3354750507,609.6 -0.605619079,51.33237147089999,609.6 -0.6027994342,51.32943389300001,609.6 -0.5995129781,51.32669342169999,609.6 -0.5957945826,51.3241790693,609.6 -0.5916836731,51.3219174496,609.6 -0.5872238101,51.31993249780001,609.6 -0.5824622279,51.3182452181,609.6 -0.5774493358,51.3168734627,609.6 -0.5722381866,51.3158317441,609.6 -0.5668839175,51.3151310822,609.6 -0.5614431705,51.3147788885,609.6 -0.5559734962,51.3147788885,609.6 -0.5505327491000001,51.3151310822,609.6 -0.5451784801,51.3158317441,609.6 -0.5399673309,51.3168734627,609.6 -0.5349544388,51.3182452181,609.6 -0.5301928566,51.31993249780001,609.6 -0.5257329936,51.3219174496,609.6 -0.5216220841,51.3241790693,609.6 -0.5179036886,51.32669342169999,609.6 -0.5146172324,51.32943389300001,609.6 -0.5117975876999999,51.33237147089999,609.6 -0.5094747019,51.3354750507,609.6 -0.5076732786,51.33871176369999,609.6 -0.5064125113,51.3420473242,609.6 -0.5057058767,51.3454463918,609.6 -0.5055609864,51.34887294570001,609.6 -0.5059795018,51.35229066549999,609.6 -0.5069571105,51.3556633166,609.6 -0.5084835673,51.3589551344,609.6 -0.5105427974,51.36213120399999,609.6 -0.5131130626,51.3651578309,609.6 -0.5161671879,51.3680029,609.6 -0.5196728463,51.3706362166,609.6 -0.5235928997,51.37302982840001,609.6 -0.5278857915,51.3751583236,609.6 -0.5325059873,51.3769991016,609.6 -0.5374044587,51.3785326144,609.6 -0.5425292053,51.37974257490001,609.6 -0.5478258091,51.3806161316,609.6 -0.5532380153000001,51.3811440053,609.6 -0.5587083333,51.3813205885,609.6 + + + + +
+ + EGRU126B FAIROAKS RWY 06 + 511907N 0003712W -
511934N 0003739W -
512003N 0003626W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to
511936N 0003558W -
511907N 0003712W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6199333333,51.318625,609.6 -0.5994920556,51.3266777222,609.6 -0.6023993034,51.3290671078,609.6 -0.6049511893,51.33161090240001,609.6 -0.6071268889,51.3342884167,609.6 -0.6275583333,51.3262388889,609.6 -0.6199333333,51.318625,609.6 + + + + +
+ + EGRU126C FAIROAKS RWY 24 + 512239N 0002949W -
512212N 0002922W -
512142N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to
512210N 0003104W -
512239N 0002949W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4969416667,51.37758888890001,609.6 -0.5178943056,51.3693692222,609.6 -0.5149878589,51.3669779903,609.6 -0.5124379479,51.3644324142,609.6 -0.5102653056000001,51.36175325,609.6 -0.4893055556,51.369975,609.6 -0.4969416667,51.37758888890001,609.6 + + + + +
+ + EGRU127A DENHAM + A circle, 2 NM radius, centred at 513518N 0003047W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5129944444,51.6217164382,609.6 -0.5184936191,51.62153986119999,609.6 -0.5239343742,51.621012006,609.6 -0.5292589149,51.6201384801,609.6 -0.5344106889,51.6189285623,609.6 -0.5393349903,51.6173951042,609.6 -0.5439795438,51.6155543924,609.6 -0.5482950621,51.6134259744,609.6 -0.5522357706,51.6110324506,609.6 -0.5557598936,51.608399232,609.6 -0.5588300976,51.60555427029999,609.6 -0.5614138859,51.60252775930001,609.6 -0.5634839411,51.5993518132,609.6 -0.5650184115,51.59606012529999,609.6 -0.5660011389,51.5926876095,609.6 -0.5664218254,51.589270029,609.6 -0.5662761375000001,51.585843617,609.6 -0.5655657464,51.5824446922,609.6 -0.5642983056999999,51.57910927410001,609.6 -0.5624873639,51.57587270119999,609.6 -0.5601522173,51.5727692576,609.6 -0.5573177001,51.5698318103,609.6 -0.5540139185,51.5670914623,609.6 -0.5502759287,51.56457722420001,609.6 -0.5461433639,51.56231570839999,609.6 -0.5416600139,51.56033084849999,609.6 -0.5368733613,51.55864364759999,609.6 -0.5318340803,51.5572719567,609.6 -0.5265955023,51.5562302872,609.6 -0.5212130538999999,51.5555296584,609.6 -0.5157436739,51.5551774815,609.6 -0.510245215,51.5551774815,609.6 -0.504775835,51.5555296584,609.6 -0.4993933866,51.5562302872,609.6 -0.4941548086,51.5572719567,609.6 -0.4891155276,51.55864364759999,609.6 -0.484328875,51.56033084849999,609.6 -0.4798455249,51.56231570839999,609.6 -0.4757129602,51.56457722420001,609.6 -0.4719749703,51.5670914623,609.6 -0.4686711888000001,51.5698318103,609.6 -0.4658366715999999,51.5727692576,609.6 -0.4635015249,51.57587270119999,609.6 -0.4616905832,51.57910927410001,609.6 -0.4604231424,51.5824446922,609.6 -0.4597127514,51.585843617,609.6 -0.4595670635,51.589270029,609.6 -0.4599877499,51.5926876095,609.6 -0.4609704774,51.59606012529999,609.6 -0.4625049477,51.5993518132,609.6 -0.464575003,51.60252775930001,609.6 -0.4671587913,51.60555427029999,609.6 -0.4702289953,51.608399232,609.6 -0.4737531183000001,51.6110324506,609.6 -0.4776938267,51.6134259744,609.6 -0.4820093451,51.6155543924,609.6 -0.4866538986,51.6173951042,609.6 -0.4915782,51.6189285623,609.6 -0.4967299739,51.6201384801,609.6 -0.5020545147,51.621012006,609.6 -0.5074952698,51.62153986119999,609.6 -0.5129944444,51.6217164382,609.6 + + + + +
+ + EGRU127B DENHAM RWY 06 + 513336N 0003432W -
513404N 0003459W -
513431N 0003344W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513404N 0003317W -
513336N 0003432W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5756055556,51.5599277778,609.6 -0.5547771667,51.56767425,609.6 -0.5576101111,51.57010516770001,609.6 -0.5600801312,51.5726852958,609.6 -0.5621670833,51.5753936389,609.6 -0.5829861111,51.56765,609.6 -0.5756055556,51.5599277778,609.6 + + + + +
+ + EGRU127C DENHAM RWY 24 + 513700N 0002704W -
513632N 0002637W -
513605N 0002750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513633N 0002816W -
513700N 0002704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.450975,51.6166444444,609.6 -0.4711767778000001,51.60916325,609.6 -0.4683454518999999,51.6067302115,609.6 -0.4658782366,51.6041480831,609.6 -0.4637951944,51.6014379167,609.6 -0.4435833333,51.6089222222,609.6 -0.450975,51.6166444444,609.6 + + + + +
+ + EGRU127D DENHAM RWY 12 + 513623N 0003455W -
513652N 0003431W -
513629N 0003322W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513600N 0003347W -
513623N 0003455W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5820527778,51.6064472222,609.6 -0.5630313056,51.6001324167,609.6 -0.5611342148,51.6028946338,609.6 -0.5588447291,51.6055390603,609.6 -0.5561814443999999,51.6080441389,609.6 -0.57525,51.61437500000001,609.6 -0.5820527778,51.6064472222,609.6 + + + + +
+ + EGRU127E DENHAM RWY 30 + 513416N 0002641W -
513347N 0002706W -
513409N 0002810W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513437N 0002746W -
513416N 0002641W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4448222222000001,51.57097499999999,609.6 -0.4628163333,51.57697613890001,609.6 -0.464678404,51.5742051095,609.6 -0.4669335187,51.5715499091,609.6 -0.4695632778,51.5690321389,609.6 -0.4516166667,51.5630472222,609.6 -0.4448222222000001,51.57097499999999,609.6 + + + + +
+ + EGRU128A LONDON HEATHROW + A circle, 2.5 NM radius, centred at 512839N 0002741W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.46135,51.519198392,609.6 -0.4675046258,51.5190207088,609.6 -0.4736065998,51.5184891791,609.6 -0.4796037246,51.51760834980001,609.6 -0.4854447065999999,51.5163857558,609.6 -0.4910795983,51.5148318544,609.6 -0.4964602286,51.51295993590001,609.6 -0.5015406165,51.5107860084,609.6 -0.5062773666,51.50832866060001,609.6 -0.5106300405,51.5056089011,609.6 -0.5145615031,51.5026499783,609.6 -0.5180382389,51.49947718029999,609.6 -0.5210306378,51.4961176176,609.6 -0.5235132452,51.4925999902,609.6 -0.5254649770000001,51.4889543421,609.6 -0.526869296,51.4852118033,609.6 -0.5277143491,51.48140432329999,609.6 -0.5279930642,51.47756439840001,609.6 -0.5277032055999999,51.4737247933,609.6 -0.5268473884,51.4699182621,609.6 -0.5254330514,51.46617726860001,609.6 -0.5234723888,51.46253370969999,609.6 -0.5209822419,51.4590186443,609.6 -0.5179839515,51.4556620291,609.6 -0.5145031729,51.4524924637,609.6 -0.510569654,51.4495369488,609.6 -0.5062169801,51.4468206561,609.6 -0.5014822864,51.4443667159,609.6 -0.4964059411,51.4421960211,609.6 -0.4910312023,51.4403270501,609.6 -0.4854038501,51.4387757108,609.6 -0.479571799,51.4375552059,609.6 -0.4735846922,51.436675922,609.6 -0.4674934822,51.436145341,609.6 -0.46135,51.43596797760001,609.6 -0.4552065178,51.436145341,609.6 -0.4491153078,51.436675922,609.6 -0.443128201,51.4375552059,609.6 -0.4372961499,51.4387757108,609.6 -0.4316687977,51.4403270501,609.6 -0.4262940589,51.4421960211,609.6 -0.4212177136,51.4443667159,609.6 -0.4164830199,51.4468206561,609.6 -0.412130346,51.4495369488,609.6 -0.4081968271,51.4524924637,609.6 -0.4047160485,51.4556620291,609.6 -0.4017177581,51.4590186443,609.6 -0.3992276111999999,51.46253370969999,609.6 -0.3972669486000001,51.46617726860001,609.6 -0.3958526116,51.4699182621,609.6 -0.3949967944000001,51.4737247933,609.6 -0.3947069358,51.47756439840001,609.6 -0.3949856508999999,51.48140432329999,609.6 -0.395830704,51.4852118033,609.6 -0.3972350230000001,51.4889543421,609.6 -0.3991867548,51.4925999902,609.6 -0.4016693622,51.4961176176,609.6 -0.4046617611,51.49947718029999,609.6 -0.4081384969,51.5026499783,609.6 -0.4120699595000001,51.5056089011,609.6 -0.4164226334,51.50832866060001,609.6 -0.4211593835,51.5107860084,609.6 -0.4262397714,51.51295993590001,609.6 -0.4316204017,51.5148318544,609.6 -0.4372552934000001,51.5163857558,609.6 -0.4430962754,51.51760834980001,609.6 -0.4490934002,51.5184891791,609.6 -0.4551953742000001,51.5190207088,609.6 -0.46135,51.519198392,609.6 + + + + +
+ + EGRU128B LONDON HEATHROW RWY 09L + 512814N 0003325W -
512902N 0003325W -
512903N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512814N 0003137W -
512814N 0003325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5569003333,51.4704933333,609.6 -0.5270472778,51.4706154722,609.6 -0.5277391047,51.473972328,609.6 -0.5279918993,51.4773531895,609.6 -0.527803899,51.4807356961,609.6 -0.52717625,51.48409747220001,609.6 -0.5570173333,51.48397538890001,609.6 -0.5569003333,51.4704933333,609.6 + + + + +
+ + EGRU128C LONDON HEATHROW RWY 27R + 512905N 0002141W -
512816N 0002141W -
512816N 0002344W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512904N 0002344W -
512905N 0002141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3613735833,51.4846374722,609.6 -0.3956410556000001,51.4845450833,609.6 -0.3949547368,51.4811877781,609.6 -0.3947077047,51.4778067502,609.6 -0.3949014835999999,51.47442436730001,609.6 -0.3955346944,51.471063,609.6 -0.3612565833,51.47115541669999,609.6 -0.3613735833,51.4846374722,609.6 + + + + +
+ + EGRU128D LONDON HEATHROW RWY 09R + 512728N 0003315W -
512817N 0003316W -
512817N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512729N 0003112W -
512728N 0003315W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5542044167,51.45779225,609.6 -0.5200781389,51.4579273056,609.6 -0.5225554954,51.46113478249999,609.6 -0.5245850906,51.4644627941,609.6 -0.5261519863,51.4678869878,609.6 -0.5272446111,51.4713823056,609.6 -0.5543178889,51.47127436110001,609.6 -0.5542044167,51.45779225,609.6 + + + + +
+ + EGRU128E LONDON HEATHROW RWY 27L + 512819N 0002144W -
512730N 0002144W -
512730N 0002408W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512819N 0002343W -
512819N 0002144W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3622085,51.4719051944,609.6 -0.3953535278,51.4718188333,609.6 -0.3963867682,51.4683164757,609.6 -0.397895493,51.46488210049999,609.6 -0.3998685359,51.4615408393,609.6 -0.4022913611,51.4583171389,609.6 -0.3620950278,51.4584231111,609.6 -0.3622085,51.4719051944,609.6 + + + + +
+ + EGRU129A NORTHOLT + A circle, 2 NM radius, centred at 513310N 0002511W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4197222222,51.5860694194,609.6 -0.4252170924999999,51.58589284140001,609.6 -0.4306535891,51.5853649835,609.6 -0.4359739627,51.58449145300001,609.6 -0.4411217051,51.5832815289,609.6 -0.4460421536,51.5817480627,609.6 -0.4506830738000001,51.5799073411,609.6 -0.4549952171,51.5777789117,609.6 -0.4589328445,51.5753853748,609.6 -0.4624542133000001,51.5727521418,609.6 -0.4655220189,51.56990716420001,609.6 -0.4681037901,51.5668806359,609.6 -0.4701722306,51.5637046715,609.6 -0.4717055057,51.56041296439999,609.6 -0.4726874696,51.5570404286,609.6 -0.4731078322,51.5536228274,609.6 -0.4729622633,51.5501963944,609.6 -0.4722524326,51.5467974485,609.6 -0.4709859873,51.54346200929999,609.6 -0.4691764654,51.5402254156,609.6 -0.4668431476,51.53712195180001,609.6 -0.4640108489,51.53418448519999,609.6 -0.4607096516,51.5314441189,609.6 -0.4569745846,51.5289298638,609.6 -0.45284525,51.5266683326,609.6 -0.4483654033,51.5246834591,609.6 -0.4435824903,51.5229962465,609.6 -0.4385471456000001,51.521624546,609.6 -0.4333126589,51.5205828693,609.6 -0.4279344138,51.51988223559999,609.6 -0.4224693049,51.5195300562,609.6 -0.4169751395,51.5195300562,609.6 -0.4115100306,51.51988223559999,609.6 -0.4061317855,51.5205828693,609.6 -0.4008972988,51.521624546,609.6 -0.3958619541,51.5229962465,609.6 -0.3910790411,51.5246834591,609.6 -0.3865991945000001,51.5266683326,609.6 -0.3824698599,51.5289298638,609.6 -0.3787347928,51.5314441189,609.6 -0.3754335956,51.53418448519999,609.6 -0.3726012968,51.53712195180001,609.6 -0.3702679791,51.5402254156,609.6 -0.3684584571999999,51.54346200929999,609.6 -0.3671920117999999,51.5467974485,609.6 -0.3664821812,51.5501963944,609.6 -0.3663366122,51.5536228274,609.6 -0.3667569749,51.5570404286,609.6 -0.3677389388,51.56041296439999,609.6 -0.3692722138,51.5637046715,609.6 -0.3713406543,51.5668806359,609.6 -0.3739224255,51.56990716420001,609.6 -0.3769902312,51.5727521418,609.6 -0.3805115998999999,51.5753853748,609.6 -0.3844492274,51.5777789117,609.6 -0.3887613706,51.5799073411,609.6 -0.3934022908,51.5817480627,609.6 -0.3983227393,51.5832815289,609.6 -0.4034704818,51.58449145300001,609.6 -0.4087908553,51.5853649835,609.6 -0.414227352,51.58589284140001,609.6 -0.4197222222,51.5860694194,609.6 + + + + +
+ + EGRU129B NORTHOLT RWY 07 + 513150N 0002942W -
513221N 0003000W -
513244N 0002819W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513214N 0002801W -
513150N 0002942W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4949055556,51.5306527778,609.6 -0.466825,51.53710075,609.6 -0.4689011239999999,51.5398120238,609.6 -0.4705770388,51.54262895259999,609.6 -0.4718390278,51.5455286111,609.6 -0.4998722221999999,51.5390916667,609.6 -0.4949055556,51.5306527778,609.6 + + + + +
+ + EGRU129C NORTHOLT RWY 25 + 513430N 0002035W -
513400N 0002017W -
513335N 0002203W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513406N 0002221W -
513430N 0002035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3429888889,51.5750055556,609.6 -0.3724551111,51.5682804444,609.6 -0.3704066466,51.5655610198,609.6 -0.3687601003,51.5627375531,609.6 -0.3675288056,51.55983305560001,609.6 -0.3380138889,51.5665694444,609.6 -0.3429888889,51.5750055556,609.6 + + + + +
+ + EGRU130A LONDON LUTON + A circle, 2.5 NM radius, centred at 515229N 0002206W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3684444444,51.9162427857,609.6 -0.3746532062,51.91606511220001,609.6 -0.3808088511,51.91553361169999,609.6 -0.3868587204,51.9146528312,609.6 -0.3927510676,51.91343030509999,609.6 -0.3984355044,51.9118764909,609.6 -0.4038634347,51.9100046782,609.6 -0.4089884723,51.9078308751,609.6 -0.4137668395,51.9053736697,609.6 -0.4181577423,51.90265407,609.6 -0.4221237193999999,51.8996953238,609.6 -0.4256309617,51.89652271809999,609.6 -0.4286495997,51.8931633624,609.6 -0.4311539569,51.8896459557,609.6 -0.4331227659,51.8860005403,609.6 -0.4345393464,51.8822582448,609.6 -0.4353917437,51.8784510169,609.6 -0.4356728262,51.8746113507,609.6 -0.4353803413,51.870772009,609.6 -0.4345169299,51.8669657435,609.6 -0.4330900986,51.8632250155,609.6 -0.4311121514,51.8595817194,609.6 -0.4286000794,51.8560669116,609.6 -0.4255754131,51.8527105458,609.6 -0.4220640341,51.8495412194,609.6 -0.4180959529,51.8465859299,609.6 -0.41370505,51.84386984689999,609.6 -0.408928787,51.8414160983,609.6 -0.4038078861000001,51.8392455744,609.6 -0.3983859841,51.83737675170001,609.6 -0.3927092619,51.8358255363,609.6 -0.3868260530000001,51.8346051295,609.6 -0.3807864345,51.8337259165,609.6 -0.3746418038,51.8331953784,609.6 -0.3684444444,51.8330180294,609.6 -0.3622470850999999,51.8331953784,609.6 -0.3561024544,51.8337259165,609.6 -0.3500628358,51.8346051295,609.6 -0.344179627,51.8358255363,609.6 -0.3385029048,51.83737675170001,609.6 -0.3330810028,51.8392455744,609.6 -0.3279601019,51.8414160983,609.6 -0.3231838389,51.84386984689999,609.6 -0.318792936,51.8465859299,609.6 -0.3148248548,51.8495412194,609.6 -0.3113134758,51.8527105458,609.6 -0.3082888095,51.8560669116,609.6 -0.3057767375,51.8595817194,609.6 -0.3037987903,51.8632250155,609.6 -0.302371959,51.8669657435,609.6 -0.3015085476,51.870772009,609.6 -0.3012160627,51.8746113507,609.6 -0.3014971452,51.8784510169,609.6 -0.3023495425,51.8822582448,609.6 -0.303766123,51.8860005403,609.6 -0.3057349319,51.8896459557,609.6 -0.3082392892,51.8931633624,609.6 -0.3112579272,51.89652271809999,609.6 -0.3147651695,51.8996953238,609.6 -0.3187311466,51.90265407,609.6 -0.3231220494,51.9053736697,609.6 -0.3279004166,51.9078308751,609.6 -0.3330254542,51.9100046782,609.6 -0.3384533845,51.9118764909,609.6 -0.3441378213,51.91343030509999,609.6 -0.3500301685,51.9146528312,609.6 -0.3560800378,51.91553361169999,609.6 -0.3622356827,51.91606511220001,609.6 -0.3684444444,51.9162427857,609.6 + + + + +
+ + EGRU130B LONDON LUTON RWY 07 + 515120N 0002706W -
515151N 0002720W -
515204N 0002605W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to
515133N 0002551W -
515120N 0002706W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4515333333,51.8555694444,609.6 -0.4308439444000001,51.8591609444,609.6 -0.4324842643,51.8619845779,609.6 -0.4337918297000001,51.8648740476,609.6 -0.4347598055999999,51.8678143333,609.6 -0.4554361110999999,51.864225,609.6 -0.4515333333,51.8555694444,609.6 + + + + +
+ + EGRU130C LONDON LUTON RWY 25 + 515336N 0001711W -
515305N 0001657W -
515253N 0001808W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to
515324N 0001822W -
515336N 0001711W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2864888889,51.8934305556,609.6 -0.3060048333,51.8900711944,609.6 -0.3043708809,51.88724578839999,609.6 -0.3030704243,51.8843548473,609.6 -0.3021101667,51.8814134167,609.6 -0.2825805556,51.884775,609.6 -0.2864888889,51.8934305556,609.6 + + + + +
+ + EGRU131A ELSTREE + A circle, 2 NM radius, centred at 513921N 0001933W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.32585,51.68911605390001,609.6 -0.3313573375,51.68893947859999,609.6 -0.3368061684,51.68841162860001,609.6 -0.3421386119,51.6875381112,609.6 -0.3472980312,51.6863282054,609.6 -0.3522296393,51.68479476259999,609.6 -0.3568810829999999,51.6829540693,609.6 -0.3612030018,51.680825673,609.6 -0.365149553,51.6784321737,609.6 -0.3686788992,51.67579898259999,609.6 -0.3717536515000001,51.672954051,609.6 -0.3743412651,51.6699275723,609.6 -0.3764143825,51.66675166080001,609.6 -0.3779511197,51.66346000930001,609.6 -0.378935295,51.6600875314,609.6 -0.3793565956,51.6566699898,609.6 -0.3792106819,51.65324361759999,609.6 -0.3784992283,51.6498447329,609.6 -0.3772298997,51.6465093546,609.6 -0.3754162653999999,51.64327282090001,609.6 -0.3730776505000001,51.64016941549999,609.6 -0.3702389262,51.6372320048,609.6 -0.3669302437,51.6344916913,609.6 -0.3631867112000001,51.6319774852,609.6 -0.3590480206,51.62971599849999,609.6 -0.3545580267,51.62773116449999,609.6 -0.3497642823,51.62604398559999,609.6 -0.3447175366,51.6246723128,609.6 -0.3394711997,51.62363065710001,609.6 -0.3340807801,51.6229300376,609.6 -0.3286033007,51.62257786529999,609.6 -0.3230966993,51.62257786529999,609.6 -0.3176192199,51.6229300376,609.6 -0.3122288003,51.62363065710001,609.6 -0.3069824634,51.6246723128,609.6 -0.3019357177,51.62604398559999,609.6 -0.2971419733,51.62773116449999,609.6 -0.2926519794,51.62971599849999,609.6 -0.2885132888,51.6319774852,609.6 -0.2847697563,51.6344916913,609.6 -0.2814610738,51.6372320048,609.6 -0.2786223495,51.64016941549999,609.6 -0.2762837346,51.64327282090001,609.6 -0.2744701003,51.6465093546,609.6 -0.2732007717,51.6498447329,609.6 -0.2724893181,51.65324361759999,609.6 -0.2723434044,51.6566699898,609.6 -0.272764705,51.6600875314,609.6 -0.2737488803,51.66346000930001,609.6 -0.2752856175,51.66675166080001,609.6 -0.2773587349,51.6699275723,609.6 -0.2799463485,51.672954051,609.6 -0.2830211008,51.67579898259999,609.6 -0.286550447,51.6784321737,609.6 -0.2904969982,51.680825673,609.6 -0.294818917,51.6829540693,609.6 -0.2994703607,51.68479476259999,609.6 -0.3044019688,51.6863282054,609.6 -0.3095613881,51.6875381112,609.6 -0.3148938316,51.68841162860001,609.6 -0.3203426625,51.68893947859999,609.6 -0.32585,51.68911605390001,609.6 + + + + +
+ + EGRU131B ELSTREE RWY 08 + 513834N 0002401W -
513906N 0002410W -
513916N 0002246W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513844N 0002236W -
513834N 0002401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.40025,51.6427944444,609.6 -0.3767162778,51.6454770833,609.6 -0.3780102409,51.64837118879999,609.6 -0.3788797193999999,51.6513260665,609.6 -0.3793175556,51.6543176667,609.6 -0.4028416667,51.6516361111,609.6 -0.40025,51.6427944444,609.6 + + + + +
+ + EGRU131C ELSTREE RWY 26 + 514008N 0001505W -
513936N 0001456W -
513926N 0001621W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513958N 0001630W -
514008N 0001505W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.251425,51.66880833330001,609.6 -0.2749615278,51.6661527222,609.6 -0.2736733649,51.6632575555,609.6 -0.2728102231,51.6603019573,609.6 -0.2723790556,51.65731000000001,609.6 -0.2488333333,51.65996666670001,609.6 -0.251425,51.66880833330001,609.6 + + + + +
+ + EGRU132A LONDON GATWICK + A circle, 2.5 NM radius, centred at 510853N 0001125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1902777778,51.1896729688,609.6 -0.1963884086,51.1894952774,609.6 -0.2024467658,51.1889637232,609.6 -0.2084010264,51.1880828533,609.6 -0.214200265,51.1868602024,609.6 -0.2197948925,51.1853062283,609.6 -0.225137083,51.1834342212,609.6 -0.2301811851,51.1812601899,609.6 -0.2348841136,51.1788027231,609.6 -0.2392057194,51.1760828302,609.6 -0.2431091322,51.1731237601,609.6 -0.2465610756,51.1699508017,609.6 -0.2495321498,51.1665910662,609.6 -0.2519970809,51.16307325490001,609.6 -0.2539349337,51.15942741280001,609.6 -0.2553292873,51.1556846713,609.6 -0.2561683713,51.1518769815,609.6 -0.2564451617,51.1480368411,609.6 -0.2561574367,51.1441970168,609.6 -0.2553077906,51.1403902646,609.6 -0.2539036069,51.1366490502,609.6 -0.2519569908,51.1330052727,609.6 -0.2494846615,51.1294899933,609.6 -0.2465078063,51.1261331707,609.6 -0.243051896,51.1229634069,609.6 -0.2391464653,51.12000770460001,609.6 -0.2348248596,51.1172912377,609.6 -0.2301239488,51.11483713860001,609.6 -0.2250838137,51.1126663019,609.6 -0.2197474041,51.1107972077,609.6 -0.2141601747,51.10924576549999,609.6 -0.2083696995,51.1080251793,609.6 -0.202425269,51.10714583639999,609.6 -0.1963774741,51.1066152198,609.6 -0.1902777778,51.1064378445,609.6 -0.1841780815,51.1066152198,609.6 -0.1781302865,51.10714583639999,609.6 -0.1721858561,51.1080251793,609.6 -0.1663953808,51.10924576549999,609.6 -0.1608081514,51.1107972077,609.6 -0.1554717418,51.1126663019,609.6 -0.1504316067,51.11483713860001,609.6 -0.145730696,51.1172912377,609.6 -0.1414090902,51.12000770460001,609.6 -0.1375036596,51.1229634069,609.6 -0.1340477492,51.1261331707,609.6 -0.131070894,51.1294899933,609.6 -0.1285985648,51.1330052727,609.6 -0.1266519486,51.1366490502,609.6 -0.1252477649,51.1403902646,609.6 -0.1243981188,51.1441970168,609.6 -0.1241103939,51.1480368411,609.6 -0.1243871843,51.1518769815,609.6 -0.1252262682,51.1556846713,609.6 -0.1266206218,51.15942741280001,609.6 -0.1285584746,51.16307325490001,609.6 -0.1310234057,51.1665910662,609.6 -0.13399448,51.1699508017,609.6 -0.1374464234,51.1731237601,609.6 -0.1413498362,51.1760828302,609.6 -0.1456714419,51.1788027231,609.6 -0.1503743705,51.1812601899,609.6 -0.1554184725,51.1834342212,609.6 -0.1607606631,51.1853062283,609.6 -0.1663552906,51.1868602024,609.6 -0.1721545292,51.1880828533,609.6 -0.1781087898,51.1889637232,609.6 -0.1841671469,51.1894952774,609.6 -0.1902777778,51.1896729688,609.6 + + + + +
+ + EGRU132B LONDON GATWICK RWY 08L + 510801N 0001635W -
510832N 0001646W -
510844N 0001523W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510812N 0001514W -
510801N 0001635W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2763583333,51.13347222219999,609.6 -0.2538749722,51.1365861111,609.6 -0.2550266082,51.13950194939999,609.6 -0.255840969,51.1424624516,609.6 -0.25631375,51.1454521944,609.6 -0.2794138889,51.1422527778,609.6 -0.2763583333,51.13347222219999,609.6 + + + + +
+ + EGRU132C LONDON GATWICK RWY 26R + 510954N 0000652W -
510922N 0000641W -
510916N 0000730W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510947N 0000743W -
510954N 0000652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1143222222,51.1650083333,609.6 -0.1285487778,51.16305747220001,609.6 -0.126990203,51.1602170511,609.6 -0.1257617811,51.1573133081,609.6 -0.1248698611,51.15436138890001,609.6 -0.1112583333,51.15622777780001,609.6 -0.1143222222,51.1650083333,609.6 + + + + +
+ + EGRU132D LONDON GATWICK RWY 08R + 510755N 0001630W -
510826N 0001641W -
510837N 0001522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510806N 0001511W -
510755N 0001630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2750777778,51.13181388890001,609.6 -0.2530278889,51.1348706667,609.6 -0.2543771033,51.1377494398,609.6 -0.2553931703,51.14068189130001,609.6 -0.25607075,51.1436527778,609.6 -0.2781333333,51.1405944444,609.6 -0.2750777778,51.13181388890001,609.6 + + + + +
+ + EGRU132E LONDON GATWICK RWY 26L + 510953N 0000613W -
510921N 0000602W -
510909N 0000728W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510941N 0000739W -
510953N 0000613W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1036388889,51.1646583333,609.6 -0.1275807778,51.1613735,609.6 -0.1262195947,51.15849728829999,609.6 -0.1251916959,51.1555668638,609.6 -0.1245023611,51.1525974722,609.6 -0.100575,51.1558805556,609.6 -0.1036388889,51.1646583333,609.6 + + + + +
+ + EGRU133A REDHILL + 511134N 0001048W thence clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511230N 0000511W -
511134N 0001048W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.18,51.1927777778,609.6 -0.0863888889,51.2083333333,609.6 -0.08577830810000001,51.2117007276,609.6 -0.0857454411,51.2150907095,609.6 -0.0862619904,51.2184651944,609.6 -0.0873227125,51.2217891473,609.6 -0.08891670810000001,51.2250280504,609.6 -0.09102753099999999,51.2281482618,609.6 -0.0936333542,51.231117366,609.6 -0.09670719309999999,51.23390451120001,609.6 -0.1002171832,51.2364807312,609.6 -0.1041269087,51.2388192469,609.6 -0.1083957801,51.24089574650001,609.6 -0.1129794553,51.242688639,609.6 -0.1178303017,51.24417928,609.6 -0.1228978922,51.2453521666,609.6 -0.1281295323,51.2461950995,609.6 -0.1334708104,51.2466993108,609.6 -0.1388661674,51.2468595556,609.6 -0.144259478,51.24667416699999,609.6 -0.1495946383,51.24614507329999,609.6 -0.1548161531,51.2452777785,609.6 -0.1598697169,51.2440813036,609.6 -0.1647027819,51.24256809340001,609.6 -0.1692651072,51.2407538854,609.6 -0.1735092831,51.2386575454,609.6 -0.1773912259,51.2363008705,609.6 -0.1808706361,51.23370836099999,609.6 -0.1839114173,51.230906965,609.6 -0.1864820495,51.2279257965,609.6 -0.1885559151,51.22479583219999,609.6 -0.1901115721,51.2215495885,609.6 -0.1911329731,51.2182207829,609.6 -0.1916096276,51.2148439831,609.6 -0.1915367066,51.21145424760001,609.6 -0.1909150876,51.20808676159999,609.6 -0.1897513404,51.20477647189999,609.6 -0.1880576543,51.2015577241,609.6 -0.1858517068,51.1984639072,609.6 -0.1831564762,51.1955271077,609.6 -0.18,51.1927777778,609.6 + + + + +
+ + EGRU133B REDHILL RWY 07L + 511150N 0001237W -
511221N 0001251W -
511235N 0001129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511204N 0001116W -
511150N 0001237W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2102416667,51.1971527778,609.6 -0.1877980556,51.2010925556,609.6 -0.1893926122,51.2039255796,609.6 -0.1905742304,51.2068373717,609.6 -0.1913332222,51.20980422220001,609.6 -0.2140805556,51.2058111111,609.6 -0.2102416667,51.1971527778,609.6 + + + + +
+ + EGRU133C REDHILL RWY 25R + 511354N 0000400W -
511323N 0000347W -
511308N 0000511W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511339N 0000526W -
511354N 0000400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.06679722220000001,51.231575,609.6 -0.0904669444,51.22744897220001,609.6 -0.08867417470000001,51.2246628442,609.6 -0.0872889642,51.2217865477,609.6 -0.08632252780000001,51.2188435278,609.6 -0.0629555556,51.2229166667,609.6 -0.06679722220000001,51.231575,609.6 + + + + +
+ + EGRU133D REDHILL RWY 07R + 511146N 0001243W -
511218N 0001257W -
511233N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511202N 0001115W -
511146N 0001243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2119305556,51.19623611109999,609.6 -0.1873991111,51.2004910278,609.6 -0.18908136,51.2033034861,609.6 -0.1903533425,51.2061997519,609.6 -0.1912046389,51.20915625,609.6 -0.2157277778,51.2049027778,609.6 -0.2119305556,51.19623611109999,609.6 + + + + +
+ + EGRU133E REDHILL RWY 25L + 511351N 0000355W -
511320N 0000342W -
511305N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511336N 0000524W -
511351N 0000355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0653694444,51.23088888889999,609.6 -0.0899130833,51.22666225,609.6 -0.08823586479999999,51.2238484928,609.6 -0.0869696108,51.2209512348,609.6 -0.0861245556,51.2179940833,609.6 -0.0615722222,51.2222222222,609.6 -0.0653694444,51.23088888889999,609.6 + + + + +
+ + EGRU133F REDHILL RWY 18 + 511545N 0000848W -
511545N 0000756W -
511448N 0000758W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511447N 0000849W -
511545N 0000848W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1465555556,51.2626111111,609.6 -0.1470106389,51.24646522220001,609.6 -0.1422509249,51.2468036602,609.6 -0.1374619454,51.2468710493,609.6 -0.1326828333,51.2466668333,609.6 -0.1322333333,51.2624527778,609.6 -0.1465555556,51.2626111111,609.6 + + + + +
+ + EGRU133G REDHILL RWY 36 + 510959N 0000806W -
510959N 0000857W -
511153N 0000854W -
511202N 0000802W -
510959N 0000806W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1349666667,51.1662944444,609.6 -0.1339975833,51.2004327778,609.6 -0.1483735833,51.19804275,609.6 -0.1492611111,51.1664555556,609.6 -0.1349666667,51.1662944444,609.6 + + + + +
+ + EGRU133H REDHILL RWY H07 + 511147N 0001226W -
511218N 0001240W -
511230N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511159N 0001113W -
511147N 0001226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2073083333,51.19628888889999,609.6 -0.1869276111,51.19981977780001,609.6 -0.1887082862,51.2026087033,609.6 -0.1900816288,51.2054871169,609.6 -0.1910363889,51.2084315833,609.6 -0.2111,51.2049555556,609.6 -0.2073083333,51.19628888889999,609.6 + + + + +
+ + EGRU133I REDHILL RWY H25 + 511345N 0000415W -
511314N 0000401W -
511302N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511333N 0000522W -
511345N 0000415W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.07071388889999999,51.2291944444,609.6 -0.08945697219999998,51.2259695,609.6 -0.0878808339,51.22313219359999,609.6 -0.0867187109,51.22021718879999,609.6 -0.0859799722,51.21724825,609.6 -0.0669194444,51.2205277778,609.6 -0.07071388889999999,51.2291944444,609.6 + + + + +
+ + EGRU133J REDHILL RWY H18 + 511528N 0000927W -
511530N 0000836W -
511449N 0000832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511442N 0000923W -
511528N 0000927W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.157575,51.2578166667,609.6 -0.1562663333,51.2449930556,609.6 -0.1516398746,51.24586868730001,609.6 -0.146905405,51.24647597479999,609.6 -0.1421024444,51.24681013890001,609.6 -0.1432805556,51.2583888889,609.6 -0.157575,51.2578166667,609.6 + + + + +
+ + EGRU133K REDHILL RWY H36 + 511002N 0000802W -
511000N 0000854W -
511151N 0000905W -
511200N 0000814W -
511002N 0000802W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1340222222,51.1672388889,609.6 -0.1373332778,51.1998783889,609.6 -0.1514294722,51.1975344444,609.6 -0.1482888889,51.1666666667,609.6 -0.1340222222,51.1672388889,609.6 + + + + +
+ + EGRU134A BIGGIN HILL + A circle, 2.5 NM radius, centred at 511951N 0000157E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0325,51.37244943980001,609.6 0.02636507,51.372271753,609.6 0.0202826224,51.3717402124,609.6 0.0143046872,51.37085936500001,609.6 0.008482393,51.36963674569999,609.6 0.0028655268,51.368082812,609.6 -0.0024978947,51.3662108541,609.6 -0.0075620381,51.3640368805,609.6 -0.012283647,51.3615794797,609.6 -0.0166224123,51.3588596609,609.6 -0.0205413175,51.3559006727,609.6 -0.0240069543,51.35272780330001,609.6 -0.0269898066,51.34936816370001,609.6 -0.0294645007,51.3458504545,609.6 -0.0314100192,51.3422047201,609.6 -0.0328098769,51.3384620911,609.6 -0.0336522578,51.3346545178,609.6 -0.0339301114,51.330814497,609.6 -0.033641208,51.32697479440001,609.6 -0.0327881536,51.3231681648,609.6 -0.0313783621,51.3194270729,609.6 -0.0294239879,51.31578341669999,609.6 -0.0269418177,51.3122682561,609.6 -0.0239531235,51.3089115485,609.6 -0.0204834779,51.3057418948,609.6 -0.0165625336,51.3027862964,609.6 -0.0122237683,51.3000699262,609.6 -0.0075041985,51.2976159153,609.6 -0.0024440638,51.2954451573,609.6 0.0029135158,51.29357613139999,609.6 0.008522905900000001,51.2920247463,609.6 0.0143363443,51.29080420519999,609.6 0.0203043458,51.289924895,609.6 0.0263761198,51.2893942982,609.6 0.0325,51.2892169295,609.6 0.0386238802,51.2893942982,609.6 0.0446956542,51.289924895,609.6 0.0506636557,51.29080420519999,609.6 0.0564770941,51.2920247463,609.6 0.0620864842,51.29357613139999,609.6 0.0674440638,51.2954451573,609.6 0.07250419850000001,51.2976159153,609.6 0.0772237683,51.3000699262,609.6 0.0815625336,51.3027862964,609.6 0.08548347789999999,51.3057418948,609.6 0.08895312349999998,51.3089115485,609.6 0.09194181770000001,51.3122682561,609.6 0.09442398790000001,51.31578341669999,609.6 0.0963783621,51.3194270729,609.6 0.09778815359999998,51.3231681648,609.6 0.09864120799999999,51.32697479440001,609.6 0.09893011139999999,51.330814497,609.6 0.0986522578,51.3346545178,609.6 0.0978098769,51.3384620911,609.6 0.0964100192,51.3422047201,609.6 0.0944645007,51.3458504545,609.6 0.09198980660000002,51.34936816370001,609.6 0.0890069543,51.35272780330001,609.6 0.08554131750000001,51.3559006727,609.6 0.0816224123,51.3588596609,609.6 0.077283647,51.3615794797,609.6 0.0725620381,51.3640368805,609.6 0.06749789470000001,51.3662108541,609.6 0.06213447319999999,51.368082812,609.6 0.056517607,51.36963674569999,609.6 0.0506953128,51.37085936500001,609.6 0.0447173776,51.3717402124,609.6 0.03863493,51.372271753,609.6 0.0325,51.37244943980001,609.6 + + + + +
+ + EGRU134B BIGGIN HILL RWY 03 + 511700N 0000013E -
511714N 0000033W -
511744N 0000010W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to
511730N 0000037E -
511700N 0000013E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0037444444,51.28320277779999,609.6 0.0102089167,51.2916319722,609.6 0.0057608933,51.2927401761,609.6 0.0014515666,51.2940463129,609.6 -0.0026966944,51.29554361109999,609.6 -0.009169444400000001,51.2871,609.6 0.0037444444,51.28320277779999,609.6 + + + + +
+ + EGRU134C BIGGIN HILL RWY 21 + 512251N 0000346E -
512236N 0000432E -
512158N 0000403E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to
512212N 0000316E -
512251N 0000346E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0627277778,51.38069444439999,609.6 0.0545643611,51.3700889167,609.6 0.05902709,51.368990418,609.6 0.0633514721,51.3676932629,609.6 0.0675149722,51.3662042222,609.6 0.0756722222,51.3767972222,609.6 0.0627277778,51.38069444439999,609.6 + + + + +
+ + EGRU135A LONDON CITY + A circle, 2 NM radius, centred at 513019N 0000319E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0551777778,51.5385224685,609.6 0.049688635,51.5383458893,609.6 0.04425780480000001,51.5378180277,609.6 0.0389429762,51.5369444912,609.6 0.0338005981,51.53573455860001,609.6 0.0288852764,51.5342010816,609.6 0.0242491907,51.5323603469,609.6 0.0199415384,51.53023190230001,609.6 0.0160080105,51.527838348,609.6 0.0124903067,51.5252050956,609.6 0.0094256923,51.5223600968,609.6 0.0068466052,51.5193335456,609.6 0.0047803132,51.5161575568,609.6 0.0032486287,51.512865824,609.6 0.0022676808,51.5094932614,609.6 0.001847749,51.5060756327,609.6 0.0019931596,51.50264917169999,609.6 0.0027022447,51.4992501975,609.6 0.0039673655,51.4959147301,609.6 0.005774998199999999,51.49267810879999,609.6 0.0081058824,51.489574618,609.6 0.0109352292,51.48663712559999,609.6 0.0142329877,51.4838967349,609.6 0.0179641657,51.4813824572,609.6 0.0220892021,51.4791209055,609.6 0.0265643871,51.4771360138,609.6 0.0313423241,51.47544878560001,609.6 0.0363724312,51.4740770724,609.6 0.0416014737,51.473035386,609.6 0.0469741258,51.4723347457,609.6 0.05243355169999999,51.471982563,609.6 0.0579220039,51.471982563,609.6 0.0633814298,51.4723347457,609.6 0.06875408180000001,51.473035386,609.6 0.0739831244,51.4740770724,609.6 0.07901323139999999,51.47544878560001,609.6 0.0837911685,51.4771360138,609.6 0.0882663534,51.4791209055,609.6 0.0923913899,51.4813824572,609.6 0.0961225678,51.4838967349,609.6 0.0994203263,51.48663712559999,609.6 0.1022496732,51.489574618,609.6 0.1045805574,51.49267810879999,609.6 0.1063881901,51.4959147301,609.6 0.1076533108,51.4992501975,609.6 0.1083623959,51.50264917169999,609.6 0.1085078065,51.5060756327,609.6 0.1080878748,51.5094932614,609.6 0.1071069268,51.512865824,609.6 0.1055752423,51.5161575568,609.6 0.1035089504,51.5193335456,609.6 0.1009298632,51.5223600968,609.6 0.09786524889999999,51.5252050956,609.6 0.094347545,51.527838348,609.6 0.0904140172,51.53023190230001,609.6 0.0861063648,51.5323603469,609.6 0.0814702792,51.5342010816,609.6 0.0765549574,51.53573455860001,609.6 0.0714125794,51.5369444912,609.6 0.06609775079999999,51.5378180277,609.6 0.06066692059999999,51.5383458893,609.6 0.0551777778,51.5385224685,609.6 + + + + +
+ + EGRU135B LONDON CITY RWY 09 + 513012N 0000136W -
513044N 0000133W -
513041N 0000010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513009N 0000007E -
513012N 0000136W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0265288333,51.50327555559999,609.6 0.0020265,51.5023953889,609.6 0.0018316307,51.50539711759999,609.6 0.0020711489,51.5083975865,609.6 0.0027431944,51.5113723611,609.6 -0.0258050833,51.5122523333,609.6 -0.0265288333,51.50327555559999,609.6 + + + + +
+ + EGRU135C LONDON CITY RWY 27 + 513026N 0000814E -
512953N 0000811E -
512957N 0000627E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513029N 0000630E -
513026N 0000814E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1372346667,51.5071330556,609.6 0.1083335278,51.5080571389,609.6 0.1085236627,51.5050552868,609.6 0.1082794163,51.5020549588,609.6 0.1076028611,51.4990805833,609.6 0.136511,51.49815627780001,609.6 0.1372346667,51.5071330556,609.6 + + + + +
+ + EGRU136A STAPLEFORD + A circle, 2 NM radius, centred at 513909N 0000922E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1560083333,51.6857966284,609.6 0.1505013986,51.685620053,609.6 0.1450529662,51.68509220280001,609.6 0.1397209126,51.684218685,609.6 0.1345618705,51.68300877859999,609.6 0.129630623,51.681475335,609.6 0.1249795192,51.6796346408,609.6 0.1206579162,51.67750624340001,609.6 0.1167116533,51.6751127429,609.6 0.1131825649,51.67247955050001,609.6 0.110108037,51.6696346173,609.6 0.1075206121,51.66660813710001,609.6 0.1054476458,51.66343222390001,609.6 0.1039110205,51.6601405706,609.6 0.1029269166,51.6567680908,609.6 0.1025056463,51.6533505473,609.6 0.1026515488,51.6499241731,609.6 0.1033629501,51.6465252864,609.6 0.1046321855,51.6431899062,609.6 0.1064456869,51.6399533706,609.6 0.1087841307,51.6368499633,609.6 0.1116226474,51.63391255079999,609.6 0.1149310881,51.6311722356,609.6 0.1186743472,51.6286580279,609.6 0.1228127354,51.6263965398,609.6 0.1273024016,51.62441170450001,609.6 0.132095796,51.6227245245,609.6 0.1371421734,51.6213528508,609.6 0.1423881274,51.6203111944,609.6 0.1477781538,51.61961057449999,609.6 0.1532552335,51.61925840200001,609.6 0.1587614331,51.61925840200001,609.6 0.1642385129,51.61961057449999,609.6 0.1696285392,51.6203111944,609.6 0.1748744933,51.6213528508,609.6 0.1799208706,51.6227245245,609.6 0.1847142651,51.62441170450001,609.6 0.1892039312,51.6263965398,609.6 0.1933423195,51.6286580279,609.6 0.1970855786,51.6311722356,609.6 0.2003940193,51.63391255079999,609.6 0.2032325359,51.6368499633,609.6 0.2055709798,51.6399533706,609.6 0.2073844812,51.6431899062,609.6 0.2086537166,51.6465252864,609.6 0.2093651178,51.6499241731,609.6 0.2095110204,51.6533505473,609.6 0.2090897501,51.6567680908,609.6 0.2081056462,51.6601405706,609.6 0.2065690208,51.66343222390001,609.6 0.2044960546,51.66660813710001,609.6 0.2019086297,51.6696346173,609.6 0.1988341018,51.67247955050001,609.6 0.1953050134,51.6751127429,609.6 0.1913587504,51.67750624340001,609.6 0.1870371475,51.6796346408,609.6 0.1823860437,51.681475335,609.6 0.1774547962,51.68300877859999,609.6 0.172295754,51.684218685,609.6 0.1669637005,51.68509220280001,609.6 0.161515268,51.685620053,609.6 0.1560083333,51.6857966284,609.6 + + + + +
+ + EGRU136B STAPLEFORD RWY 03L + 513634N 0000654E -
513653N 0000612E -
513743N 0000708E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513724N 0000750E -
513634N 0000654E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.114975,51.6095305556,609.6 0.1306218889,51.62320063889999,609.6 0.1264803317,51.6247434871,609.6 0.1225788083,51.62651232070001,609.6 0.1189490556,51.62849275,609.6 0.1032222222,51.61475,609.6 0.114975,51.6095305556,609.6 + + + + +
+ + EGRU136C STAPLEFORD RWY 21R + 514140N 0001141E -
514122N 0001223E -
514037N 0001132E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514056N 0001050E -
514140N 0001141E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1946944444,51.6945361111,609.6 0.1804416944,51.6821273889,609.6 0.1846372067,51.6806366835,609.6 0.1885991606,51.6789167892,609.6 0.1922952778,51.67698175,609.6 0.2064694444,51.6893194444,609.6 0.1946944444,51.6945361111,609.6 + + + + +
+ + EGRU136D STAPLEFORD RWY 03R + 513634N 0000656E -
513652N 0000613E -
513742N 0000710E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513723N 0000752E -
513634N 0000656E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1154222222,51.6093166667,609.6 0.1311190278,51.62303599999999,609.6 0.126951311,51.6245517675,609.6 0.1230198351,51.6262951166,609.6 0.1193565833,51.6282518611,609.6 0.1036666667,51.61453611109999,609.6 0.1154222222,51.6093166667,609.6 + + + + +
+ + EGRU136E STAPLEFORD RWY 21L + 514140N 0001143E -
514121N 0001225E -
514036N 0001134E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514055N 0001051E -
514140N 0001143E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1951388889,51.6943527778,609.6 0.1809234167,51.68197180559999,609.6 0.1850942614,51.6804547511,609.6 0.1890278444,51.678710016,609.6 0.1926921111,51.67675183330001,609.6 0.2069138889,51.6891361111,609.6 0.1951388889,51.6943527778,609.6 + + + + +
+ + EGRU137A LONDON STANSTED + A circle, 2.5 NM radius, centred at 515306N 0001406E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.235,51.9266121564,609.6 0.2287898076,51.92643448310001,609.6 0.2226327443,51.92590298339999,609.6 0.2165814812,51.9250222041,609.6 0.2106877765,51.9237996799,609.6 0.2050020304,51.9222458679,609.6 0.1995728501,51.92037405800001,609.6 0.1944466326,51.9182002582,609.6 0.1896671656,51.9157430564,609.6 0.1852752525,51.9130234609,609.6 0.1813083633,51.9100647192,609.6 0.1778003149,51.90689211849999,609.6 0.1747809834,51.9035327683,609.6 0.1722760514,51.9000153673,609.6 0.1703067912,51.896369958,609.6 0.1688898867,51.8926276688,609.6 0.1680372953,51.8888204475,609.6 0.1677561503,51.8849807881,609.6 0.1680487046,51.8811414532,609.6 0.1689123167,51.87733519460001,609.6 0.1703394781,51.8735944735,609.6 0.1723178822,51.8699511843,609.6 0.1748305335,51.8664363832,609.6 0.1778558969,51.86308002400001,609.6 0.1813680845,51.8599107037,609.6 0.1853370792,51.85695542020001,609.6 0.1897289923,51.8542393427,609.6 0.1945063538,51.851785599,609.6 0.1996284322,51.8496150796,609.6 0.2050515805,51.84774626079999,609.6 0.2107296074,51.84619504860001,609.6 0.2166141682,51.8449746444,609.6 0.2226551744,51.8440954332,609.6 0.2288012169,51.8435648963,609.6 0.235,51.8433875477,609.6 0.2411987831,51.8435648963,609.6 0.2473448256,51.8440954332,609.6 0.2533858318,51.8449746444,609.6 0.2592703926,51.84619504860001,609.6 0.2649484195,51.84774626079999,609.6 0.2703715678,51.8496150796,609.6 0.2754936462,51.851785599,609.6 0.2802710077,51.8542393427,609.6 0.2846629208,51.85695542020001,609.6 0.2886319155,51.8599107037,609.6 0.2921441031,51.86308002400001,609.6 0.2951694665,51.8664363832,609.6 0.2976821178,51.8699511843,609.6 0.2996605219,51.8735944735,609.6 0.3010876833,51.87733519460001,609.6 0.3019512954,51.8811414532,609.6 0.3022438497,51.8849807881,609.6 0.3019627047,51.8888204475,609.6 0.3011101133,51.8926276688,609.6 0.2996932088,51.896369958,609.6 0.2977239486,51.9000153673,609.6 0.2952190166,51.9035327683,609.6 0.2921996851,51.90689211849999,609.6 0.2886916367,51.9100647192,609.6 0.2847247475,51.9130234609,609.6 0.2803328344,51.9157430564,609.6 0.2755533674,51.9182002582,609.6 0.2704271499,51.92037405800001,609.6 0.2649979696,51.9222458679,609.6 0.2593122235,51.9237996799,609.6 0.2534185188,51.9250222041,609.6 0.2473672557,51.92590298339999,609.6 0.2412101924,51.92643448310001,609.6 0.235,51.9266121564,609.6 + + + + +
+ + EGRU137B LONDON STANSTED RWY 04 + 515028N 0001044E -
515050N 0001005E -
515128N 0001103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515106N 0001141E -
515028N 0001044E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1788194444,51.8410361111,609.6 0.1947456944,51.85167430559999,609.6 0.1909710506,51.8535562167,609.6 0.187424914,51.8556015888,609.6 0.1841257222,51.85779980560001,609.6 0.1681888889,51.84715277780001,609.6 0.1788194444,51.8410361111,609.6 + + + + +
+ + EGRU137C LONDON STANSTED RWY 22 + 515552N 0001739E -
515530N 0001817E -
515444N 0001709E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515506N 0001630E -
515552N 0001739E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2941833333,51.93113055560001,609.6 0.2750736667,51.9184224444,609.6 0.2788639154,51.916548197,609.6 0.2824255347,51.9145097839,609.6 0.28574,51.91231783329999,609.6 0.3048388889,51.9250166667,609.6 0.2941833333,51.93113055560001,609.6 + + + + +
+ + EGRU138A ANDREWSFIELD + A circle, 2 NM radius, centred at 515342N 0002657E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4491666667,51.9282896919,609.6 0.4436301033,51.9281131227,609.6 0.4381523581,51.927585291,609.6 0.4327916200999999,51.926711804,609.6 0.4276048275,51.9255019406,609.6 0.422647059,51.9239685519,609.6 0.4179709460000001,51.92212792399999,609.6 0.4136261113,51.9199996043,609.6 0.4096586409,51.91760619210001,609.6 0.4061105941,51.9149730981,609.6 0.4030195576,51.9121282729,609.6 0.4004182481,51.90910190909999,609.6 0.3983341674,51.90592612,609.6 0.3967893144,51.9026345974,609.6 0.3957999552,51.8992622536,609.6 0.3953764561,51.89584485030001,609.6 0.3955231779999999,51.8924186188,609.6 0.3962384364,51.88901987600001,609.6 0.3975145241,51.88568463899999,609.6 0.3993377987,51.8824482445,609.6 0.4016888316,51.8793449744,609.6 0.4045426185,51.8764076934,609.6 0.4078688481,51.8736675024,609.6 0.4116322255,51.87115341000001,609.6 0.4157928483000001,51.86889202660001,609.6 0.4203066295,51.86690728399999,609.6 0.4251257647,51.86522018340001,609.6 0.4301992364,51.86384857459999,609.6 0.4354733526,51.86280696779999,609.6 0.4408923116999999,51.8621063813,609.6 0.4463987897999999,51.8617542257,609.6 0.4519345435,51.8617542257,609.6 0.4574410216,51.8621063813,609.6 0.4628599807,51.86280696779999,609.6 0.4681340969,51.86384857459999,609.6 0.4732075687,51.86522018340001,609.6 0.4780267038,51.86690728399999,609.6 0.4825404851000001,51.86889202660001,609.6 0.4867011077999999,51.87115341000001,609.6 0.4904644852,51.8736675024,609.6 0.4937907147999999,51.8764076934,609.6 0.4966445018,51.8793449744,609.6 0.4989955347,51.8824482445,609.6 0.5008188092,51.88568463899999,609.6 0.502094897,51.88901987600001,609.6 0.5028101553,51.8924186188,609.6 0.5029568773,51.89584485030001,609.6 0.5025333781,51.8992622536,609.6 0.5015440189,51.9026345974,609.6 0.4999991659,51.90592612,609.6 0.4979150853,51.90910190909999,609.6 0.4953137757,51.9121282729,609.6 0.4922227392,51.9149730981,609.6 0.4886746924,51.91760619210001,609.6 0.484707222,51.9199996043,609.6 0.4803623874,51.92212792399999,609.6 0.4756862743,51.9239685519,609.6 0.4707285057999999,51.9255019406,609.6 0.4655417132,51.926711804,609.6 0.4601809752,51.927585291,609.6 0.45470323,51.9281131227,609.6 0.4491666667,51.9282896919,609.6 + + + + +
+ + EGRU138B ANDREWSFIELD RWY 09L + 515311N 0002223E -
515343N 0002219E -
515348N 0002344E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515316N 0002348E -
515311N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3730888889,51.8864027778,609.6 0.3966865556,51.88766425,609.6 0.3958296993000001,51.89062131390001,609.6 0.3954070986,51.89361413149999,609.6 0.3954222778,51.8966183333,609.6 0.3718527778,51.8953583333,609.6 0.3730888889,51.8864027778,609.6 + + + + +
+ + EGRU138C ANDREWSFIELD RWY 27R + 515413N 0003137E -
515341N 0003142E -
515336N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515408N 0003006E -
515413N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5269916667,51.9035638889,609.6 0.5016900556,51.9022398056,609.6 0.5025295237,51.89928078159999,609.6 0.502934256,51.89628698540001,609.6 0.5029010556,51.8932828056,609.6 0.5282305556,51.89460833329999,609.6 0.5269916667,51.9035638889,609.6 + + + + +
+ + EGRU138D ANDREWSFIELD RWY 09R + 515310N 0002223E -
515342N 0002218E -
515347N 0002343E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515315N 0002348E -
515310N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3729722222,51.8861333333,609.6 0.3967850555999999,51.8873999167,609.6 0.3958892902,51.8903525916,609.6 0.3954272954,51.89334320879999,609.6 0.3954029167000001,51.8963474167,609.6 0.3717416667,51.8950888889,609.6 0.3729722222,51.8861333333,609.6 + + + + +
+ + EGRU138E ANDREWSFIELD RWY 27L + 515412N 0003137E -
515340N 0003142E -
515335N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515407N 0003006E -
515412N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5270416667,51.9032611111,609.6 0.50179325,51.90194663890001,609.6 0.502589532,51.8989830515,609.6 0.5029506279,51.8959871214,609.6 0.5028736667,51.89298324999999,609.6 0.5282722222,51.8943055556,609.6 0.5270416667,51.9032611111,609.6 + + + + +
+ + EGRU139A ROCHESTER + A circle, 2 NM radius, centred at 512107N 0003010E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5028888889000001,51.38515667770001,609.6 0.4974181135,51.3849800946,609.6 0.4920054548,51.3844522212,609.6 0.4867084083,51.38357866499999,609.6 0.4815832334,51.38236870509999,609.6 0.4766843526000001,51.3808351933,609.6 0.4720637707999999,51.3789944163,609.6 0.4677705203,51.3768659223,609.6 0.4638501395999999,51.3744723119,609.6 0.4603441886,51.3718389969,609.6 0.4572898085000001,51.3689939296,609.6 0.4547193289,51.3659673044,609.6 0.4526599272,51.3627912369,609.6 0.4511333435,51.3594994211,609.6 0.4501556536,51.3561267721,609.6 0.4497371038,51.3527090546,609.6 0.4498820067,51.349282503,609.6 0.4505887009,51.3458834377,609.6 0.4518495739000001,51.3425478795,609.6 0.4536511481,51.3393111687,609.6 0.4559742281999999,51.336207591,609.6 0.4587941085999999,51.3332700152,609.6 0.4620808394,51.3305295459,609.6 0.4657995454,51.3280151953,609.6 0.4699107981,51.3257535772,609.6 0.4743710333,51.32376862689999,609.6 0.4791330128999999,51.3220813485,609.6 0.4841463232,51.3207095942,609.6 0.4893579071999999,51.3196678763,609.6 0.4947126227999999,51.3189672149,609.6 0.5001538236,51.3186150215,609.6 0.5056239541999999,51.3186150215,609.6 0.511065155,51.3189672149,609.6 0.5164198706000001,51.3196678763,609.6 0.5216314546,51.3207095942,609.6 0.5266447649,51.3220813485,609.6 0.5314067444,51.32376862689999,609.6 0.5358669797,51.3257535772,609.6 0.5399782323,51.3280151953,609.6 0.5436969384,51.3305295459,609.6 0.5469836691,51.3332700152,609.6 0.5498035496,51.336207591,609.6 0.5521266296,51.3393111687,609.6 0.5539282038,51.3425478795,609.6 0.5551890769,51.3458834377,609.6 0.5558957711,51.349282503,609.6 0.5560406739,51.3527090546,609.6 0.5556221241,51.3561267721,609.6 0.5546444343,51.3594994211,609.6 0.5531178505,51.3627912369,609.6 0.5510584489,51.3659673044,609.6 0.5484879693,51.3689939296,609.6 0.5454335892,51.3718389969,609.6 0.5419276382,51.3744723119,609.6 0.5380072574,51.3768659223,609.6 0.533714007,51.3789944163,609.6 0.5290934252,51.3808351933,609.6 0.5241945444,51.38236870509999,609.6 0.5190693695,51.38357866499999,609.6 0.5137723229,51.3844522212,609.6 0.5083596643,51.3849800946,609.6 0.5028888889000001,51.38515667770001,609.6 + + + + +
+ + EGRU139B ROCHESTER RWY 02L + 511821N 0002901E -
511833N 0002812E -
511920N 0002842E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
511909N 0002931E -
511821N 0002901E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4834861111,51.3058194444,609.6 0.4918709444,51.3192941389,609.6 0.4872282527,51.320048953,609.6 0.4827129256000001,51.321062879,609.6 0.4783616944,51.32232766670001,609.6 0.4701277777999999,51.30908888889999,609.6 0.4834861111,51.3058194444,609.6 + + + + +
+ + EGRU139C ROCHESTER RWY 20R + 512359N 0003136E -
512347N 0003224E -
512250N 0003148E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
512302N 0003100E -
512359N 0003136E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5266194444,51.3997527778,609.6 0.51678675,51.38399999999999,609.6 0.5213616864,51.3830840819,609.6 0.5257857540999999,51.381913545,609.6 0.5300228333,51.38049794440001,609.6 0.5400055556,51.3964833333,609.6 0.5266194444,51.3997527778,609.6 + + + + +
+ + EGRU139D ROCHESTER RWY 02R + 511819N 0002902E -
511831N 0002814E -
511920N 0002844E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
511909N 0002933E -
511819N 0002902E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4839722222,51.3053888889,609.6 0.4924984444,51.3192133056,609.6 0.4878400458,51.31993329260001,609.6 0.4833041184,51.3209135101,609.6 0.4789275833000001,51.3221459722,609.6 0.4705972222,51.3086333333,609.6 0.4839722222,51.3053888889,609.6 + + + + +
+ + EGRU139E ROCHESTER RWY 20L + 512354N 0003134E -
512342N 0003222E -
512249N 0003149E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
512302N 0003102E -
512354N 0003134E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5259916667,51.3983277778,609.6 0.5170946389,51.3839471944,609.6 0.5216613468,51.38301395450001,609.6 0.5260746936,51.381826592,609.6 0.5302986389,51.38039480560001,609.6 0.5393916667,51.3950861111,609.6 0.5259916667,51.3983277778,609.6 + + + + +
+ + EGRU140A LASHENDEN/HEADCORN + A circle, 2 NM radius, centred at 510923N 0003840E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6444444444,51.1896827956,609.6 0.6389968451,51.1895062075,609.6 0.6336071153,51.188978319,609.6 0.6283325063,51.1881047377,609.6 0.6232290383,51.1868947429,609.6 0.6183509028,51.1853611865,609.6 0.6137498838,51.1835203555,609.6 0.6094748059,51.1813917985,609.6 0.6055710142,51.17899811629999,609.6 0.6020798931,51.17636472139999,609.6 0.5990384267,51.1735195665,609.6 0.5964788084,51.1704928469,609.6 0.5944281011,51.1673166787,609.6 0.5929079536,51.16402475700001,609.6 0.591934375,51.1606519978,609.6 0.5915175691,51.1572341668,609.6 0.5916618315,51.1538074997,609.6 0.5923655088999999,51.150408318,609.6 0.5936210222,51.14707264390001,609.6 0.5954149519,51.1438358191,609.6 0.5977281846,51.1407321305,609.6 0.6005361204,51.1377944485,609.6 0.6038089363,51.13505387880001,609.6 0.6075119051,51.1325394351,609.6 0.6116057653,51.1302777326,609.6 0.6160471368,51.12829270739999,609.6 0.6207889809,51.1266053649,609.6 0.6257810968999999,51.1252335582,609.6 0.6309706512,51.12419180039999,609.6 0.6363027343,51.123491112,609.6 0.6417209384,51.123138905,609.6 0.6471679504,51.123138905,609.6 0.6525861545,51.123491112,609.6 0.6579182377,51.12419180039999,609.6 0.663107792,51.1252335582,609.6 0.668099908,51.1266053649,609.6 0.6728417521,51.12829270739999,609.6 0.6772831236,51.1302777326,609.6 0.6813769837,51.1325394351,609.6 0.6850799526,51.13505387880001,609.6 0.6883527685,51.1377944485,609.6 0.6911607043,51.1407321305,609.6 0.693473937,51.1438358191,609.6 0.6952678667,51.14707264390001,609.6 0.69652338,51.150408318,609.6 0.6972270574,51.1538074997,609.6 0.6973713198,51.1572341668,609.6 0.6969545139,51.1606519978,609.6 0.6959809353,51.16402475700001,609.6 0.6944607878,51.1673166787,609.6 0.6924100805,51.1704928469,609.6 0.6898504622,51.1735195665,609.6 0.6868089958,51.17636472139999,609.6 0.6833178747,51.17899811629999,609.6 0.6794140829999999,51.1813917985,609.6 0.6751390051,51.1835203555,609.6 0.6705379861,51.1853611865,609.6 0.6656598506,51.1868947429,609.6 0.6605563826,51.1881047377,609.6 0.6552817736,51.188978319,609.6 0.6498920438,51.1895062075,609.6 0.6444444444,51.1896827956,609.6 + + + + +
+ + EGRU140B LASHENDEN/HEADCORN RWY 10 + 510953N 0003359E -
511024N 0003412E -
511009N 0003544E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to
510937N 0003531E -
510953N 0003359E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5663138889,51.1645833333,609.6 0.5918729444,51.1603403333,609.6 0.5926518716,51.16330463360001,609.6 0.5938527671,51.1662126983,609.6 0.5954659167,51.1690408333,609.6 0.5699777778,51.1732722222,609.6 0.5663138889,51.1645833333,609.6 + + + + +
+ + EGRU140C LASHENDEN/HEADCORN RWY 28 + 510853N 0004319E -
510821N 0004306E -
510836N 0004136E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to
510908N 0004149E -
510853N 0004319E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7218944443999999,51.1479583333,609.6 0.6969505833,51.15213019440001,609.6 0.6961247654,51.1491710648,609.6 0.6948783343,51.1462707894,609.6 0.6932215,51.1434529722,609.6 0.7182361111,51.1392694444,609.6 0.7218944443999999,51.1479583333,609.6 + + + + +
+ + EGRU141A EARLS COLNE + A circle, 2 NM radius, centred at 515452N 0004057E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6825,51.9477340257,609.6 0.6769610427,51.947557457,609.6 0.6714809291,51.9470296268,609.6 0.6661178735,51.9461561423,609.6 0.6609288387,51.94494628230001,609.6 0.6559689273,51.94341289800001,609.6 0.6512907936,51.94157227549999,609.6 0.6469440818,51.9394439619,609.6 0.6429748979,51.9370505568,609.6 0.6394253193,51.93441747070001,609.6 0.636332949,51.9315726541,609.6 0.6337305176,51.9285462996,609.6 0.631645539,51.9253705205,609.6 0.6301000212,51.9220790084,609.6 0.6291102374,51.9187066755,609.6 0.6286865582,51.9152892834,609.6 0.6288333463,51.9118630633,609.6 0.6295489163,51.908464332,609.6 0.6308255577,51.90512910650001,609.6 0.632649622,51.9018927233,609.6 0.635001672,51.8987894642,609.6 0.6378566928,51.8958521937,609.6 0.6411843597,51.8931120127,609.6 0.6449493626,51.8905979296,609.6 0.6491117818,51.8883365545,609.6 0.6536275115,51.8863518193,609.6 0.6584487265,51.8846647251,609.6 0.6635243874,51.8832931215,609.6 0.668800779,51.8822515187,609.6 0.6742220758,51.8815509349,609.6 0.6797309292,51.8811987806,609.6 0.6852690708,51.8811987806,609.6 0.6907779241999999,51.8815509349,609.6 0.696199221,51.8822515187,609.6 0.7014756126,51.8832931215,609.6 0.7065512735000001,51.8846647251,609.6 0.7113724885,51.8863518193,609.6 0.7158882182,51.8883365545,609.6 0.7200506374,51.8905979296,609.6 0.7238156403,51.8931120127,609.6 0.7271433072,51.8958521937,609.6 0.729998328,51.8987894642,609.6 0.7323503780000001,51.9018927233,609.6 0.7341744422999998,51.90512910650001,609.6 0.7354510837,51.908464332,609.6 0.7361666536999999,51.9118630633,609.6 0.7363134417999999,51.9152892834,609.6 0.7358897625999999,51.9187066755,609.6 0.7348999788,51.9220790084,609.6 0.733354461,51.9253705205,609.6 0.7312694824,51.9285462996,609.6 0.728667051,51.9315726541,609.6 0.7255746807,51.93441747070001,609.6 0.7220251021,51.9370505568,609.6 0.7180559182000001,51.9394439619,609.6 0.7137092064,51.94157227549999,609.6 0.7090310727,51.94341289800001,609.6 0.7040711613,51.94494628230001,609.6 0.6988821265,51.9461561423,609.6 0.6935190709,51.9470296268,609.6 0.6880389573,51.947557457,609.6 0.6825,51.9477340257,609.6 + + + + +
+ + EGRU141B EARLS COLNE RWY 06 + 515309N 0003708E -
515337N 0003642E -
515405N 0003759E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515337N 0003826E -
515309N 0003708E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6188194444,51.8858888889,609.6 0.6405008056,51.89362883329999,609.6 0.6376370069,51.8960555344,609.6 0.6351382452,51.8986320512,609.6 0.6330249167000001,51.90133741670001,609.6 0.6115694444000001,51.8936777778,609.6 0.6188194444,51.8858888889,609.6 + + + + +
+ + EGRU141C EARLS COLNE RWY 24 + 515631N 0004450E -
515603N 0004516E -
515535N 0004358E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515604N 0004332E -
515631N 0004450E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7473027778,51.94202500000001,609.6 0.7256713333,51.9343375,609.6 0.7283957123,51.9318493242,609.6 0.7307458014,51.9292193892,609.6 0.7327025,51.92646913890001,609.6 0.7545583333,51.93423611109999,609.6 0.7473027778,51.94202500000001,609.6 + + + + +
+ + EGRU142A SOUTHEND + A circle, 2.5 NM radius, centred at 513413N 0004136E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6933333333,51.6118921753,609.6 0.6871661804,51.6117144943,609.6 0.6810517867,51.6111829714,609.6 0.6750424567,51.6103021536,609.6 0.6691895887,51.6090795755,609.6 0.6635432321,51.6075256945,609.6 0.6581516565,51.60565380079999,609.6 0.6530609364,51.6034799024,609.6 0.648314556,51.6010225879,609.6 0.6439530358,51.5983028658,609.6 0.6400135863999999,51.5953439844,609.6 0.6365297913,51.5921712314,609.6 0.6335313205000001,51.5888117171,609.6 0.63104368,51.5852941413,609.6 0.6290879964,51.5816485477,609.6 0.62768084,51.5779060657,609.6 0.6268340873,51.5740986447,609.6 0.6265548244,51.5702587803,609.6 0.6268452906,51.5664192368,609.6 0.6277028650000001,51.5626127676,609.6 0.6291200932,51.5588718361,609.6 0.6310847554,51.5552283386,609.6 0.6335799758,51.5517133334,609.6 0.6365843696,51.54835677650001,609.6 0.6400722293,51.5451872669,609.6 0.6440137460000001,51.5422318046,609.6 0.6483752663,51.53951556090001,609.6 0.6531195793,51.5370616655,609.6 0.6582062349,51.5348910106,609.6 0.6635918876,51.5330220742,609.6 0.6692306642,51.5314707638,609.6 0.6750745535,51.5302502819,609.6 0.6810738118,51.5293710145,609.6 0.6871773836,51.5288404435,609.6 0.6933333333,51.5286630835,609.6 0.699489283,51.5288404435,609.6 0.7055928549,51.5293710145,609.6 0.7115921131,51.5302502819,609.6 0.7174360023999999,51.5314707638,609.6 0.7230747791000001,51.5330220742,609.6 0.7284604317,51.5348910106,609.6 0.7335470874,51.5370616655,609.6 0.7382914004,51.53951556090001,609.6 0.7426529206000001,51.5422318046,609.6 0.7465944374000001,51.5451872669,609.6 0.7500822969999998,51.54835677650001,609.6 0.7530866907999999,51.5517133334,609.6 0.7555819112,51.5552283386,609.6 0.7575465735,51.5588718361,609.6 0.7589638016,51.5626127676,609.6 0.7598213761,51.5664192368,609.6 0.7601118423,51.5702587803,609.6 0.7598325793,51.5740986447,609.6 0.7589858267,51.5779060657,609.6 0.7575786702,51.5816485477,609.6 0.7556229865999999,51.5852941413,609.6 0.7531353462,51.5888117171,609.6 0.7501368754,51.5921712314,609.6 0.7466530802,51.5953439844,609.6 0.7427136308999999,51.5983028658,609.6 0.7383521107,51.6010225879,609.6 0.7336057302,51.6034799024,609.6 0.7285150102,51.60565380079999,609.6 0.7231234345000001,51.6075256945,609.6 0.7174770779,51.6090795755,609.6 0.7116242099,51.6103021536,609.6 0.7056148799,51.6111829714,609.6 0.6995004862999999,51.6117144943,609.6 0.6933333333,51.6118921753,609.6 + + + + +
+ + EGRU142B SOUTHEND RWY 05 + 513209N 0003745E -
513236N 0003714E -
513259N 0003807E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513233N 0003837E -
513209N 0003745E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6291166667,51.53595555559999,609.6 0.6436260556,51.54249894439999,609.6 0.6405434667,51.544803412,609.6 0.637734927,51.5472403342,609.6 0.6352150556,51.5497970556,609.6 0.6206805556,51.5432416667,609.6 0.6291166667,51.53595555559999,609.6 + + + + +
+ + EGRU142C SOUTHEND RWY 23 + 513615N 0004523E -
513549N 0004553E -
513527N 0004505E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513554N 0004434E -
513615N 0004523E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7563638888999999,51.6042944444,609.6 0.7428335,51.5982206389,609.6 0.7459369184,51.5959248333,609.6 0.7487662855,51.5934956228,609.6 0.7513069167,51.5909456667,609.6 0.7648138889000001,51.5970083333,609.6 0.7563638888999999,51.6042944444,609.6 + + + + +
+ + EGRU143A LONDON HELIPORT + A circle, 2 NM radius, centred at 512812N 0001046W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1795388889,51.50322266999999,609.6 -0.1850237897,51.5030460899,609.6 -0.1904504231,51.5025182256,609.6 -0.1957611449,51.5016446845,609.6 -0.2008995498,51.5004347457,609.6 -0.2058110744,51.4989012607,609.6 -0.2104435795,51.4970605163,609.6 -0.2147479056,51.4949320603,609.6 -0.2186783971,51.49253849309999,609.6 -0.2221933866,51.4899052263,609.6 -0.2252556374,51.4870602117,609.6 -0.2278327366,51.4840336435,609.6 -0.2298974372,51.48085763660001,609.6 -0.2314279437,51.47756588469999,609.6 -0.2324081392,51.4741933023,609.6 -0.2328277518,51.4707756531,609.6 -0.2326824584,51.46734917130001,609.6 -0.2319739255,51.46395017609999,609.6 -0.2307097858,51.4606146879,609.6 -0.2289035523,51.4573780459,609.6 -0.2265744705,51.4542745352,609.6 -0.22374731,51.4513370235,609.6 -0.2204520984,51.4485966148,609.6 -0.2167238008,51.4460823203,609.6 -0.2126019478,51.44382075330001,609.6 -0.2081302155,51.44183584809999,609.6 -0.2033559639,51.4401486084,609.6 -0.1983297361,51.4387768857,609.6 -0.1931047256,51.43773519200001,609.6 -0.187736216,51.4370345469,609.6 -0.1822809993,51.4366823617,609.6 -0.1767967785,51.4366823617,609.6 -0.1713415617,51.4370345469,609.6 -0.1659730521,51.43773519200001,609.6 -0.1607480417,51.4387768857,609.6 -0.1557218139,51.4401486084,609.6 -0.1509475623,51.44183584809999,609.6 -0.14647583,51.44382075330001,609.6 -0.142353977,51.4460823203,609.6 -0.1386256794,51.4485966148,609.6 -0.1353304678,51.4513370235,609.6 -0.1325033072,51.4542745352,609.6 -0.1301742255,51.4573780459,609.6 -0.128367992,51.4606146879,609.6 -0.1271038523,51.46395017609999,609.6 -0.1263953194,51.46734917130001,609.6 -0.126250026,51.4707756531,609.6 -0.1266696386,51.4741933023,609.6 -0.1276498341,51.47756588469999,609.6 -0.1291803406,51.48085763660001,609.6 -0.1312450412,51.4840336435,609.6 -0.1338221404,51.4870602117,609.6 -0.1368843911,51.4899052263,609.6 -0.1403993807,51.49253849309999,609.6 -0.1443298721,51.4949320603,609.6 -0.1486341983,51.4970605163,609.6 -0.1532667033,51.4989012607,609.6 -0.158178228,51.5004347457,609.6 -0.1633166329,51.5016446845,609.6 -0.1686273547,51.5025182256,609.6 -0.1740539881,51.5030460899,609.6 -0.1795388889,51.50322266999999,609.6 + + + + +
+ + EGRU145A KENLEY + A circle, 2 NM radius, centred at 511821N 0000536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0934361111,51.33925416229999,609.6 -0.09890142070000001,51.33907757800001,609.6 -0.1043086718,51.33854970110001,609.6 -0.1096004267,51.33767613900001,609.6 -0.1147204823,51.3364661709,609.6 -0.1196144705,51.3349326486,609.6 -0.1242304386,51.333091859,609.6 -0.1285194033,51.3309633502,609.6 -0.1324358716,51.3285697229,609.6 -0.1359383252,51.3259363892,609.6 -0.1389896597,51.3230913013,609.6 -0.1415575778,51.320064654,609.6 -0.143614929,51.3168885628,609.6 -0.1451399949,51.3135967222,609.6 -0.1461167151,51.31022404739999,609.6 -0.1465348537,51.30680630320001,609.6 -0.1463901019,51.3033797245,609.6 -0.1456841192,51.2999806319,609.6 -0.1444245102,51.2966450465,609.6 -0.1426247389,51.2934083089,609.6 -0.1403039812,51.2903047052,609.6 -0.1374869178,51.2873671045,609.6 -0.1342034687,51.2846266116,609.6 -0.1304884741,51.2821122391,609.6 -0.1263813233,51.27985060129999,609.6 -0.1219255368,51.2778656334,609.6 -0.117168306,51.2761783399,609.6 -0.1121599941,51.2748065733,609.6 -0.1069536056,51.27376484600001,609.6 -0.1016042276,51.27306417829999,609.6 -0.0961684503,51.2727119817,609.6 -0.090703772,51.2727119817,609.6 -0.08526799459999999,51.27306417829999,609.6 -0.07991861660000001,51.27376484600001,609.6 -0.0747122281,51.2748065733,609.6 -0.0697039163,51.2761783399,609.6 -0.0649466854,51.2778656334,609.6 -0.06049089900000001,51.27985060129999,609.6 -0.0563837481,51.2821122391,609.6 -0.05266875349999999,51.2846266116,609.6 -0.04938530449999999,51.2873671045,609.6 -0.046568241,51.2903047052,609.6 -0.0442474834,51.2934083089,609.6 -0.0424477121,51.2966450465,609.6 -0.0411881031,51.2999806319,609.6 -0.0404821204,51.3033797245,609.6 -0.0403373686,51.30680630320001,609.6 -0.0407555071,51.31022404739999,609.6 -0.0417322274,51.3135967222,609.6 -0.0432572932,51.3168885628,609.6 -0.0453146444,51.320064654,609.6 -0.04788256250000001,51.3230913013,609.6 -0.050933897,51.3259363892,609.6 -0.0544363506,51.3285697229,609.6 -0.05835281900000001,51.3309633502,609.6 -0.0626417836,51.333091859,609.6 -0.0672577518,51.3349326486,609.6 -0.07215174000000001,51.3364661709,609.6 -0.0772717955,51.33767613900001,609.6 -0.0825635504,51.33854970110001,609.6 -0.0879708015,51.33907757800001,609.6 -0.0934361111,51.33925416229999,609.6 + + + + +
+ + EGRU146A UPAVON + A circle, 2 NM radius, centred at 511710N 0014652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7810361111,51.3194987197,609.6 -1.7864990728,51.3193221349,609.6 -1.791904001,51.3187942564,609.6 -1.7971934828,51.3179206918,609.6 -1.8023113392,51.3167107202,609.6 -1.8072032258,51.3151771934,609.6 -1.8118172121,51.31333639830001,609.6 -1.8161043357,51.31120788320001,609.6 -1.8200191235,51.3088142487,609.6 -1.8235200746,51.30618090680001,609.6 -1.8265701009,51.3033358101,609.6 -1.8291369187,51.3003091533,609.6 -1.8311933891,51.29713305189999,609.6 -1.8327178029,51.2938412006,609.6 -1.8336941066,51.29046851470001,609.6 -1.8341120685,51.287050759,609.6 -1.8339673816,51.2836241687,609.6 -1.8332617045,51.2802250642,609.6 -1.8320026385,51.27688946710001,609.6 -1.8302036416,51.2736527181,609.6 -1.8278838816,51.2705491032,609.6 -1.8250680283,51.2676114917,609.6 -1.8217859889,51.2648709887,609.6 -1.8180725886,51.2623566068,609.6 -1.8139671997,51.2600949604,609.6 -1.8095133244,51.2581099849,609.6 -1.8047581334,51.256422685,609.6 -1.7997519687,51.255050913,609.6 -1.7945478119,51.2540091818,609.6 -1.7892007268,51.25330851129999,609.6 -1.7837672792,51.2529563133,609.6 -1.778304943,51.2529563133,609.6 -1.7728714954,51.25330851129999,609.6 -1.7675244103,51.2540091818,609.6 -1.7623202535,51.255050913,609.6 -1.7573140888,51.256422685,609.6 -1.7525588979,51.2581099849,609.6 -1.7481050225,51.2600949604,609.6 -1.7439996337,51.2623566068,609.6 -1.7402862334,51.2648709887,609.6 -1.737004194,51.2676114917,609.6 -1.7341883406,51.2705491032,609.6 -1.7318685806,51.2736527181,609.6 -1.7300695837,51.27688946710001,609.6 -1.7288105177,51.2802250642,609.6 -1.7281048407,51.2836241687,609.6 -1.7279601537,51.287050759,609.6 -1.7283781156,51.29046851470001,609.6 -1.7293544194,51.2938412006,609.6 -1.7308788332,51.29713305189999,609.6 -1.7329353036,51.3003091533,609.6 -1.7355021213,51.3033358101,609.6 -1.7385521476,51.30618090680001,609.6 -1.7420530988,51.3088142487,609.6 -1.7459678865,51.31120788320001,609.6 -1.7502550102,51.31333639830001,609.6 -1.7548689964,51.3151771934,609.6 -1.759760883,51.3167107202,609.6 -1.7648787395,51.3179206918,609.6 -1.7701682212,51.3187942564,609.6 -1.7755731495,51.3193221349,609.6 -1.7810361111,51.3194987197,609.6 + + + + +
+ + EGRU147A WESTON ON THE GREEN + A circle, 2 NM radius, centred at 515245N 0011304W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.217775,51.9124147822,609.6 -1.2233096109,51.9122382126,609.6 -1.2287854244,51.9117103797,609.6 -1.2341442722,51.9108368907,609.6 -1.2393292361,51.9096270245,609.6 -1.2442852569,51.90809363219999,609.6 -1.2489597219,51.906253,609.6 -1.2533030257,51.9041246752,609.6 -1.2572690985,51.9017312573,609.6 -1.260815896,51.8990981568,609.6 -1.2639058446,51.8962533245,609.6 -1.2665062392,51.8932269531,609.6 -1.2685895874,51.8900511559,609.6 -1.2701338983,51.8867596248,609.6 -1.2711229111,51.88338727210001,609.6 -1.2715462634,51.8799698596,609.6 -1.2713995955,51.8765436188,609.6 -1.2706845913,51.8731448665,609.6 -1.2694089551,51.8698096202,609.6 -1.2675863246,51.8665732165,609.6 -1.2652361213,51.8634699373,609.6 -1.2623833407,51.86053264780001,609.6 -1.2590582833,51.85779244870001,609.6 -1.2552962317,51.8552783487,609.6 -1.2511370741,51.85301695849999,609.6 -1.246624882,51.8510322098,609.6 -1.2418074431,51.849345104,609.6 -1.2367357568,51.8479734909,609.6 -1.2314634964,51.8469318809,609.6 -1.2260464439,51.8462312922,609.6 -1.2205419031,51.8458791355,609.6 -1.2150080969,51.8458791355,609.6 -1.2095035561,51.8462312922,609.6 -1.2040865036,51.8469318809,609.6 -1.1988142432,51.8479734909,609.6 -1.1937425569,51.849345104,609.6 -1.188925118,51.8510322098,609.6 -1.1844129259,51.85301695849999,609.6 -1.1802537683,51.8552783487,609.6 -1.1764917167,51.85779244870001,609.6 -1.1731666593,51.86053264780001,609.6 -1.1703138787,51.8634699373,609.6 -1.1679636754,51.8665732165,609.6 -1.1661410449,51.8698096202,609.6 -1.1648654087,51.8731448665,609.6 -1.1641504045,51.8765436188,609.6 -1.1640037366,51.8799698596,609.6 -1.1644270889,51.88338727210001,609.6 -1.1654161017,51.8867596248,609.6 -1.1669604126,51.8900511559,609.6 -1.1690437608,51.8932269531,609.6 -1.1716441554,51.8962533245,609.6 -1.174734104,51.8990981568,609.6 -1.1782809015,51.9017312573,609.6 -1.1822469743,51.9041246752,609.6 -1.1865902781,51.906253,609.6 -1.1912647431,51.90809363219999,609.6 -1.1962207639,51.9096270245,609.6 -1.2014057278,51.9108368907,609.6 -1.2067645756,51.9117103797,609.6 -1.2122403891,51.9122382126,609.6 -1.217775,51.9124147822,609.6 + + + + +
+ + EGRU148A LITTLE RISSINGTON + A circle, 2 NM radius, centred at 515202N 0014139W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6941888889,51.9003787396,609.6 -1.6997220206,51.9002021697,609.6 -1.7051963708,51.8996743359,609.6 -1.7105537866,51.8988008453,609.6 -1.7157373652,51.89759097699999,609.6 -1.720692062,51.8960575819,609.6 -1.7253652785,51.8942169465,609.6 -1.7297074225,51.89208861779999,609.6 -1.7336724366,51.8896951955,609.6 -1.7372182877,51.8870620902,609.6 -1.7403074122,51.88421725250001,609.6 -1.7429071136,51.8811908754,609.6 -1.744989907,51.878015072,609.6 -1.7465338071,51.8747235344,609.6 -1.7475225576,51.871351175,609.6 -1.7479457987,51.8679337555,609.6 -1.7477991716,51.8645075076,609.6 -1.74708436,51.8611087482,609.6 -1.7458090659,51.8577734948,609.6 -1.7439869233,51.8545370841,609.6 -1.7416373485,51.8514337981,609.6 -1.7387853301,51.848496502,609.6 -1.7354611608,51.8457562968,609.6 -1.7317001135,51.8432421911,609.6 -1.7275420659,51.84098079570001,609.6 -1.7230310777,51.83899604240001,609.6 -1.7182149238,51.8373089327,609.6 -1.7131445901,51.8359373164,609.6 -1.7078737356,51.83489570390001,609.6 -1.7024581275,51.8341951135,609.6 -1.6969550543,51.8338429559,609.6 -1.6914227235,51.8338429559,609.6 -1.6859196503,51.8341951135,609.6 -1.6805040421,51.83489570390001,609.6 -1.6752331877,51.8359373164,609.6 -1.670162854,51.8373089327,609.6 -1.6653467001,51.83899604240001,609.6 -1.6608357118,51.84098079570001,609.6 -1.6566776643,51.8432421911,609.6 -1.6529166169,51.8457562968,609.6 -1.6495924477,51.848496502,609.6 -1.6467404293,51.8514337981,609.6 -1.6443908545,51.8545370841,609.6 -1.6425687119,51.8577734948,609.6 -1.6412934178,51.8611087482,609.6 -1.6405786061,51.8645075076,609.6 -1.6404319791,51.8679337555,609.6 -1.6408552202,51.871351175,609.6 -1.6418439707,51.8747235344,609.6 -1.6433878708,51.878015072,609.6 -1.6454706642,51.8811908754,609.6 -1.6480703656,51.88421725250001,609.6 -1.6511594901,51.8870620902,609.6 -1.6547053411,51.8896951955,609.6 -1.6586703553,51.89208861779999,609.6 -1.6630124993,51.8942169465,609.6 -1.6676857158,51.8960575819,609.6 -1.6726404126,51.89759097699999,609.6 -1.6778239912,51.8988008453,609.6 -1.6831814069,51.8996743359,609.6 -1.6886557571,51.9002021697,609.6 -1.6941888889,51.9003787396,609.6 + + + + +
+ + EGRU148B LITTLE RISSINGTON RWY 04 + 514928N 0014421W -
514948N 0014502W -
515038N 0014358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515018N 0014317W -
514928N 0014421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7391218333,51.8243148333,609.6 -1.7213525556,51.8383616389,609.6 -1.7254230493,51.8399944628,609.6 -1.7292396587,51.8418478204,609.6 -1.7327713333,51.8439066389,609.6 -1.7505336944,51.8298625,609.6 -1.7391218333,51.8243148333,609.6 + + + + +
+ + EGRU148C LITTLE RISSINGTON RWY 22 + 515435N 0013857W -
515415N 0013816W -
515325N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515345N 0014001W -
515435N 0013857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6491845278,51.9098425278,609.6 -1.6669975556,51.89581225,609.6 -1.6629237494,51.8941777929,609.6 -1.6591049889,51.89232265580001,609.6 -1.6555723889,51.89026197219999,609.6 -1.6377523889,51.90429491670001,609.6 -1.6491845278,51.9098425278,609.6 + + + + +
+ + EGRU148D LITTLE RISSINGTON RWY 09 + 515133N 0014621W -
515205N 0014626W -
515210N 0014452W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515138N 0014449W -
515133N 0014621W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7725545278,51.8591138056,609.6 -1.7468936389,51.8604959167,609.6 -1.7476408861,51.8634648455,609.6 -1.7479527579,51.8664633953,609.6 -1.7478266389,51.8694671389,609.6 -1.7737993056,51.86806827780001,609.6 -1.7725545278,51.8591138056,609.6 + + + + +
+ + EGRU148E LITTLE RISSINGTON RWY 27 + 515236N 0013649W -
515204N 0013645W -
515158N 0013826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515230N 0013831W -
515236N 0013649W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6136181389,51.8766028056,609.6 -1.6419936111,51.8751070833,609.6 -1.641039975,51.8721608815,609.6 -1.6405194626,51.869173453,609.6 -1.64043625,51.86616913890001,609.6 -1.6123731111,51.8676483611,609.6 -1.6136181389,51.8766028056,609.6 + + + + +
+ + EGRU148F LITTLE RISSINGTON RWY 13 + 515336N 0014536W -
515400N 0014501W -
515326N 0014357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515300N 0014429W -
515336N 0014536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7599274722,51.8932725278,609.6 -1.7412547778,51.8831991667,609.6 -1.738709554,51.8857675435,609.6 -1.735799195,51.8881829232,609.6 -1.7325475278,51.8904255,609.6 -1.7503725833,51.9000425,609.6 -1.7599274722,51.8932725278,609.6 + + + + +
+ + EGRU148G LITTLE RISSINGTON RWY 31 + 515008N 0013751W -
514943N 0013825W -
515025N 0013943W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515048N 0013906W -
515008N 0013751W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6308653333,51.8354350556,609.6 -1.6516788333,51.84670925,609.6 -1.6548287542,51.8444133462,609.6 -1.6583005968,51.8423031413,609.6 -1.6620659167,51.8403958889,609.6 -1.6404065278,51.8286650278,609.6 -1.6308653333,51.8354350556,609.6 + + + + +
+ + EGRU149 HMP ASHFIELD + 512911N 0022623W -
512908N 0022602W -
512901N 0022556W -
512852N 0022556W -
512843N 0022602W -
512836N 0022619W -
512841N 0022644W -
512854N 0022652W -
512907N 0022641W -
512911N 0022623W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 405 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4396638889,51.4865194444,274.32 -2.4446388889,51.485325,274.32 -2.4478944444,51.4817361111,274.32 -2.4456416667,51.4779722222,274.32 -2.438575,51.47657222219999,274.32 -2.4337638889,51.47851944439999,274.32 -2.4321583333,51.48111666669999,274.32 -2.4321638889,51.4834777778,274.32 -2.4338861111,51.4854361111,274.32 -2.4396638889,51.4865194444,274.32 + + + + +
+ + EGRU150 HMP AYLESBURY + 514938N 0004807W -
514935N 0004742W -
514916N 0004724W -
514904N 0004732W -
514857N 0004807W -
514914N 0004830W -
514926N 0004829W -
514938N 0004807W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 311 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8018638889,51.8272222222,243.84 -0.8080638889,51.8240194444,243.84 -0.8083861111,51.8205972222,243.84 -0.8018833332999999,51.8157416667,243.84 -0.7922305556,51.8176833333,243.84 -0.7900166667,51.8210444444,243.84 -0.7949638888999999,51.82650000000001,243.84 -0.8018638889,51.8272222222,243.84 + + + + +
+ + EGRU151 HMP BELMARSH/THAMESIDE/ISIS + 513012N 0000557E -
512942N 0000624E -
512930N 0000550E -
512918N 0000540E -
512927N 0000450E -
512952N 0000501E -
513012N 0000557E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 16 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0990305556,51.5032916667,152.4 0.08349444440000001,51.4976583333,152.4 0.08043333330000001,51.4909166667,152.4 0.0945611111,51.4882305556,152.4 0.097125,51.4915305556,152.4 0.1065527778,51.4949638889,152.4 0.0990305556,51.5032916667,152.4 + + + + +
+ + EGRU152 HMP BRISTOL + 512909N 0023540W -
512905N 0023520W -
512857N 0023505W -
512849N 0023503W -
512837N 0023512W -
512834N 0023540W -
512848N 0023602W -
512901N 0023600W -
512909N 0023540W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 206 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5945583333,51.48574444439999,213.36 -2.5999805556,51.4835722222,213.36 -2.6006527778,51.4800527778,213.36 -2.5943277778,51.4762111111,213.36 -2.5866972222,51.4770777778,213.36 -2.5841138889,51.4802305556,213.36 -2.5845861111,51.4824888889,213.36 -2.5889111111,51.4847722222,213.36 -2.5945583333,51.48574444439999,213.36 + + + + +
+ + EGRU153 HMP BRIXTON + 512722N 0000738W -
512718N 0000710W -
512709N 0000703W -
512656N 0000707W -
512650N 0000721W -
512653N 0000755W -
512714N 0000758W -
512722N 0000738W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 125 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1273222222,51.4562194444,182.88 -0.132775,51.4538527778,182.88 -0.132025,51.4481638889,182.88 -0.1223611111,51.4472388889,182.88 -0.1186333333,51.4488194444,182.88 -0.1174055556,51.4525472222,182.88 -0.1195583333,51.4551111111,182.88 -0.1273222222,51.4562194444,182.88 + + + + +
+ + EGRU154 HMP BRONZEFIELD + 512610N 0002935W -
512618N 0002841W -
512554N 0002832W -
512544N 0002845W -
512541N 0002907W -
512549N 0002925W -
512610N 0002935W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 53 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4930166667,51.4362277778,152.4 -0.4903944444,51.4301416667,152.4 -0.4851722222,51.42807222220001,152.4 -0.4792944444,51.4289388889,152.4 -0.4755583333,51.43160277779999,152.4 -0.4780916667,51.4384027778,152.4 -0.4930166667,51.4362277778,152.4 + + + + +
+ + EGRU155 HMP BULLINGDON + 515113N 0010603W -
515114N 0010521W -
515103N 0010505W -
515049N 0010507W -
515037N 0010526W -
515038N 0010553W -
515050N 0010610W -
515113N 0010603W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 267 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1007305556,51.8536888889,213.36 -1.1028972222,51.84718055559999,213.36 -1.0980777778,51.84375,213.36 -1.0904388889,51.8436166667,213.36 -1.0851861111,51.8468194444,213.36 -1.0848166667,51.8508305556,213.36 -1.0891916667,51.85380833330001,213.36 -1.1007305556,51.8536888889,213.36 + + + + +
+ + EGRU156 HMP CARDIFF + 512910N 0031002W -
512854N 0030934W -
512834N 0030952W -
512831N 0031011W -
512844N 0031031W -
512902N 0031033W -
512910N 0031002W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 39 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1672138889,51.48604722219999,152.4 -3.1757305556,51.4838527778,152.4 -3.175252777799999,51.4788194444,152.4 -3.1696805556,51.475225,152.4 -3.1643611111,51.4761972222,152.4 -3.1593388889,51.4816305556,152.4 -3.1672138889,51.48604722219999,152.4 + + + + +
+ + EGRU157 HMP CHELMSFORD + 514431N 0002858E -
514416N 0002945E -
514359N 0002948E -
514351N 0002936E -
514352N 0002909E -
514404N 0002833E -
514431N 0002858E
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 135 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4828416667,51.74201111109999,182.88 0.4758444444,51.73457222220001,182.88 0.4857611110999999,51.73124444439999,182.88 0.4934583333,51.7308777778,182.88 0.4965583332999999,51.7330944444,182.88 0.4958222222,51.7377777778,182.88 0.4828416667,51.74201111109999,182.88 + + + + +
+ + EGRU158 HMP COLDINGLEY + 511938N 0003849W -
511937N 0003818W -
511917N 0003756W -
511858N 0003841W -
511917N 0003910W -
511938N 0003849W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 174 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6469388889,51.32713333329999,182.88 -0.6526472222,51.3213472222,182.88 -0.6445972222,51.3159916667,182.88 -0.6323444444,51.32135555559999,182.88 -0.6382083333,51.3268527778,182.88 -0.6469388889,51.32713333329999,182.88 + + + + +
+ + EGRU159 HMP DOWNVIEW/HIGH DOWN + 512036N 0001131W -
512039N 0001059W -
512019N 0001050W -
511952N 0001055W -
511948N 0001137W -
511959N 0001154W -
512027N 0001150W -
512036N 0001131W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 457 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1918888889,51.34335,274.32 -0.1973305556,51.34089999999999,274.32 -0.1983277778,51.3329555556,274.32 -0.1936833333,51.33009444439999,274.32 -0.1818777778,51.3310472222,274.32 -0.1805555556,51.3386166667,274.32 -0.1830305556,51.3442861111,274.32 -0.1918888889,51.34335,274.32 + + + + +
+ + EGRU160 HMP EAST SUTTON PARK + 511311N 0003654E -
511313N 0003731E -
511249N 0003733E -
511235N 0003642E -
511301N 0003632E -
511311N 0003654E
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 376 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6149277778,51.2196083333,243.84 0.6088027778,51.2168722222,243.84 0.6115416667,51.20981666670001,243.84 0.6257305556,51.213475,243.84 0.6254055556,51.2202638889,243.84 0.6149277778,51.2196083333,243.84 + + + + +
+ + EGRU161 HMP EASTWOOD PARK + 513819N 0022840W -
513823N 0022800W -
513822N 0022740W -
513803N 0022723W -
513751N 0022754W -
513747N 0022829W -
513819N 0022840W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4776472222,51.6386305556,182.88 -2.4745916667,51.6297,182.88 -2.4648611111,51.6309111111,182.88 -2.4564555556,51.6342583333,182.88 -2.4611111111,51.6395611111,182.88 -2.4666166667,51.6397694444,182.88 -2.4776472222,51.6386305556,182.88 + + + + +
+ + EGRU162 HMP ERLESTOKE + 511726N 0020243W -
511728N 0020206W -
511703N 0020205W -
511643N 0020217W -
511650N 0020308W -
511712N 0020324W -
511726N 0020243W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 360 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0452722222,51.29065277779999,243.84 -2.0567666667,51.2865527778,243.84 -2.0523444444,51.28052777780001,243.84 -2.0381527778,51.27865833330001,243.84 -2.0346833333,51.2842861111,243.84 -2.0350694444,51.29121388890001,243.84 -2.0452722222,51.29065277779999,243.84 + + + + +
+ + EGRU163 HMP FELTHAM + 512644N 0002615W -
512640N 0002532W -
512559N 0002547W -
512607N 0002647W -
512639N 0002641W -
512644N 0002615W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 62 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4374555555999999,51.4456916667,152.4 -0.4445888889,51.4440722222,152.4 -0.4464194444,51.4351611111,152.4 -0.4298361111,51.4329861111,152.4 -0.4255777777999999,51.4443638889,152.4 -0.4374555555999999,51.4456916667,152.4 + + + + +
+ + EGRU164 HMP GRENDON + 515354N 0010045W -
515352N 0010002W -
515339N 0005949W -
515321N 0005949W -
515310N 0010013W -
515317N 0010046W -
515332N 0010050W -
515354N 0010045W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 296 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0123694444,51.8984361111,213.36 -1.01375,51.8922777778,213.36 -1.0127555556,51.8879388889,213.36 -1.0036888889,51.8861833333,213.36 -0.9968944444,51.8892388889,213.36 -0.9969638889,51.8942055556,213.36 -1.0004833333,51.89774166670001,213.36 -1.0123694444,51.8984361111,213.36 + + + + +
+ + EGRU165 HMP HUNTERCOMBE + 513536N 0010124W -
513528N 0010033W -
513455N 0010046W -
513504N 0010142W -
513536N 0010124W
Upper limit: 1100 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 691 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0232222222,51.5932361111,335.28 -1.0283555556,51.5845388889,335.28 -1.0128361111,51.58186944440001,335.28 -1.0091694444,51.59106944439999,335.28 -1.0232222222,51.5932361111,335.28 + + + + +
+ + EGRU166 HMP MAIDSTONE + 511709N 0003128E -
511642N 0003202E -
511622N 0003124E -
511648N 0003046E -
511709N 0003128E
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 123 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5243527778,51.28575555560001,182.88 0.5127555556,51.2800194444,182.88 0.5232944443999999,51.2726805556,182.88 0.5339416667,51.2783527778,182.88 0.5243527778,51.28575555560001,182.88 + + + + +
+ + EGRU167 HMP PARC + 513207N 0033404W -
513211N 0033313W -
513138N 0033308W -
513133N 0033411W -
513158N 0033416W -
513207N 0033404W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 343 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5678111111,51.5352527778,243.84 -3.5710222222,51.5326472222,243.84 -3.569805555599999,51.5257222222,243.84 -3.5522638889,51.52710833329999,243.84 -3.5535388889,51.53633333329999,243.84 -3.5678111111,51.5352527778,243.84 + + + + +
+ + EGRU168 HMP PENTONVILLE + 513256N 0000726W -
513258N 0000659W -
513257N 0000641W -
513231N 0000624W -
513222N 0000721W -
513256N 0000726W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 141 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1238444444,51.54883611109999,182.88 -0.1224222222,51.5393944444,182.88 -0.1066055556,51.54205,182.88 -0.1114833333,51.5491972222,182.88 -0.1164833333,51.5494138889,182.88 -0.1238444444,51.54883611109999,182.88 + + + + +
+ + EGRU169 HMP ROCHESTER + 512226N 0002853E -
512227N 0002947E -
512201N 0003010E -
512147N 0003000E -
512136N 0002947E -
512137N 0002930E -
512226N 0002853E
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Rochester Tower (FRZ - EGRU139A) and HMPPS.
Contact: Rochester Tower 01634-869969 (Option 3 (Air Traffic Control)) Tower@rochesterairport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 326 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4812666667,51.3738055556,243.84 0.4916833333,51.3603027778,243.84 0.4963916667,51.3601055556,243.84 0.5000972222,51.3629972222,243.84 0.5027888889,51.36703333330001,243.84 0.4962694444,51.3742805556,243.84 0.4812666667,51.3738055556,243.84 + + + + +
+ + EGRU170 HMP SEND + 511647N 0002943W -
511649N 0002911W -
511610N 0002857W -
511605N 0002942W -
511620N 0002953W -
511634N 0002958W -
511647N 0002943W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 182 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4953472222,51.2797444444,182.88 -0.4993222222,51.2761944444,182.88 -0.4980666667,51.2721388889,182.88 -0.4950305555999999,51.26801388889999,182.88 -0.4824361111,51.2694277778,182.88 -0.4863444444,51.28026666669999,182.88 -0.4953472222,51.2797444444,182.88 + + + + +
+ + EGRU171 HMP SWALESIDE/ELMLEY + 512358N 0005051E -
512345N 0005148E -
512306N 0005126E -
512259N 0005101E -
512309N 0005025E -
512358N 0005051E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 73 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8475638889,51.3994277778,152.4 0.8404138889,51.3857027778,152.4 0.8501388889,51.3830972222,152.4 0.8572611110999999,51.38499722220001,152.4 0.8634527778,51.3958083333,152.4 0.8475638889,51.3994277778,152.4 + + + + +
+ + EGRU172 HMP SWANSEA + 513706N 0035719W -
513711N 0035655W -
513707N 0035636W -
513647N 0035625W -
513637N 0035706W -
513647N 0035724W -
513706N 0035719W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 27 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9554083333,51.6182055556,152.4 -3.9566,51.61305,152.4 -3.9516,51.6103583333,152.4 -3.9402194444,51.61293055559999,152.4 -3.9434361111,51.61853888889999,152.4 -3.9486805556,51.6196555556,152.4 -3.9554083333,51.6182055556,152.4 + + + + +
+ + EGRU173 HMP THE MOUNT + 514353N 0003231W -
514355N 0003207W -
514340N 0003138W -
514313N 0003213W -
514315N 0003255W -
514332N 0003253W -
514343N 0003245W -
514353N 0003231W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 539 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5418638889,51.73138888890001,304.8 -0.5458194444,51.72863888889999,304.8 -0.54795,51.72567777779999,304.8 -0.5487111111,51.72091111110001,304.8 -0.5369555556,51.7203027778,304.8 -0.5273166667,51.7278194444,304.8 -0.5353611111,51.7318416667,304.8 -0.5418638889,51.73138888890001,304.8 + + + + +
+ + EGRU174 HMP USK + 514218N 0025347W -
514153N 0025327W -
514139N 0025411W -
514205N 0025433W -
514218N 0025347W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 61 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8964611111,51.7049333333,152.4 -2.909075,51.70134166670001,152.4 -2.9031472222,51.6940388889,152.4 -2.8909361111,51.6980722222,152.4 -2.8964611111,51.7049333333,152.4 + + + + +
+ + EGRU175 HMP WANDSWORTH + 512722N 0001030W -
512653N 0001006W -
512636N 0001042W -
512659N 0001111W -
512714N 0001056W -
512722N 0001030W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 112 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1751111111,51.4561361111,182.88 -0.1822138889,51.45391944440001,182.88 -0.1864583333,51.4496,182.88 -0.1783527778,51.4432166667,182.88 -0.1683916667,51.4481388889,182.88 -0.1751111111,51.4561361111,182.88 + + + + +
+ + EGRU176 HMP WINCHESTER + 510400N 0012008W -
510409N 0011927W -
510355N 0011917W -
510334N 0011913W -
510330N 0012001W -
510400N 0012008W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 333 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3355916667,51.0667638889,243.84 -1.3336277778,51.0584444444,243.84 -1.3203583333,51.0595305556,243.84 -1.3214416667,51.06528611109999,243.84 -1.3242,51.0690611111,243.84 -1.3355916667,51.0667638889,243.84 + + + + +
+ + EGRU177 HMP WORMWOOD SCRUBS + 513116N 0001456W -
513119N 0001401W -
513047N 0001352W -
513044N 0001445W -
513057N 0001454W -
513116N 0001456W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 51 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2490222222,51.52105277780001,152.4 -0.2482861111,51.5157277778,152.4 -0.245725,51.51224999999999,152.4 -0.2311805556,51.513125,152.4 -0.2334805556,51.5218972222,152.4 -0.2490222222,51.52105277780001,152.4 + + + + +
+ + EGRU201A WEST WALES/ABERPORTH + A circle, 2 NM radius, centred at 520653N 0043334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5594166667,52.1480051098,609.6 -4.5649804396,52.14782854620001,609.6 -4.5704851043,52.1473007313,609.6 -4.5758721847,52.14642727210001,609.6 -4.5810844621,52.1452174474,609.6 -4.5860665862,52.1436841082,609.6 -4.5907656665,52.1418435403,609.6 -4.595131836,52.13971529059999,609.6 -4.5991187822,52.13732195819999,609.6 -4.6026842393,52.1346889531,609.6 -4.6057904364,52.1318442253,609.6 -4.6084044967,52.1288179668,609.6 -4.610498784,52.1256422898,609.6 -4.6120511927,52.1223508853,609.6 -4.6130453778,52.1189786645,609.6 -4.6134709236,52.11556138790001,609.6 -4.613323449,52.1121352855,609.6 -4.6126046482,52.1087366727,609.6 -4.6113222675,52.10540156540001,609.6 -4.6094900176,52.1021652986,609.6 -4.6071274234,52.0990621525,609.6 -4.6042596129,52.0961249906,609.6 -4.6009170469,52.0933849121,609.6 -4.5971351939,52.090870924,609.6 -4.5929541522,52.08860963539999,609.6 -4.588418225,52.0866249767,609.6 -4.5835754511,52.084937948,609.6 -4.5784770974,52.083566398,609.6 -4.5731771188,52.0825248361,609.6 -4.5677315897,52.0818242799,609.6 -4.5621981139,52.0814721395,609.6 -4.5566352195,52.0814721395,609.6 -4.5511017437,52.0818242799,609.6 -4.5456562145,52.0825248361,609.6 -4.5403562359,52.083566398,609.6 -4.5352578823,52.084937948,609.6 -4.5304151083,52.0866249767,609.6 -4.5258791811,52.08860963539999,609.6 -4.5216981395,52.090870924,609.6 -4.5179162864,52.0933849121,609.6 -4.5145737204,52.0961249906,609.6 -4.5117059099,52.0990621525,609.6 -4.5093433158,52.1021652986,609.6 -4.5075110659,52.10540156540001,609.6 -4.5062286851,52.1087366727,609.6 -4.5055098843,52.1121352855,609.6 -4.5053624097,52.11556138790001,609.6 -4.5057879555,52.1189786645,609.6 -4.5067821406,52.1223508853,609.6 -4.5083345493,52.1256422898,609.6 -4.5104288367,52.1288179668,609.6 -4.513042897,52.1318442253,609.6 -4.516149094,52.1346889531,609.6 -4.5197145511,52.13732195819999,609.6 -4.5237014973,52.13971529059999,609.6 -4.5280676668,52.1418435403,609.6 -4.5327667471,52.1436841082,609.6 -4.5377488713,52.1452174474,609.6 -4.5429611486,52.14642727210001,609.6 -4.548348229,52.1473007313,609.6 -4.5538528938,52.14782854620001,609.6 -4.5594166667,52.1480051098,609.6 + + + + +
+ + EGRU201B WEST WALES/ABERPORTH RWY 07 + 520543N 0043806W -
520614N 0043822W -
520633N 0043646W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to
520602N 0043630W -
520543N 0043806W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6350722222,52.0952472222,609.6 -4.6082841389,52.1004781111,609.6 -4.6101710488,52.1032481534,609.6 -4.6116450046,52.1061116413,609.6 -4.6126939167,52.1090452778,609.6 -4.6394694444,52.1038166667,609.6 -4.6350722222,52.0952472222,609.6 + + + + +
+ + EGRU201C WEST WALES/ABERPORTH RWY 25 + 520803N 0042902W -
520732N 0042846W -
520713N 0043022W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to
520744N 0043038W -
520803N 0042902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4837666667,52.13411944440001,609.6 -4.5105152222,52.12893122220001,609.6 -4.5086338997,52.12615934320001,609.6 -4.5071664244,52.12329435000001,609.6 -4.5061246944,52.1203595833,609.6 -4.4793638889,52.12555,609.6 -4.4837666667,52.13411944440001,609.6 + + + + +
+ + EGRU202A WELSHPOOL + A circle, 2 NM radius, centred at 523743N 0030912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1532972222,52.6619383097,609.6 -3.1589260268,52.66176175910001,609.6 -3.1644950299,52.661233983,609.6 -3.1699450695,52.6603605885,609.6 -3.1752182559,52.6591508538,609.6 -3.1802585903,52.6576176296,609.6 -3.1850125627,52.65577720109999,609.6 -3.1894297226,52.65364911429999,609.6 -3.1934632159,52.6512559674,609.6 -3.1970702834,52.6486231691,609.6 -3.2002127138,52.64577866800001,609.6 -3.2028572478,52.6427526543,609.6 -3.2049759285,52.6395772385,609.6 -3.2065463945,52.6362861091,609.6 -3.2075521128,52.6329141749,609.6 -3.2079825492,52.6294971935,609.6 -3.2078332746,52.6260713921,609.6 -3.2071060066,52.6226730826,609.6 -3.2058085849,52.6193382778,609.6 -3.2039548833,52.61610230880001,609.6 -3.2015646572,52.6129994526,609.6 -3.1986633301,52.61006256870001,609.6 -3.1952817199,52.6073227528,609.6 -3.19145571,52.6048090084,609.6 -3.1872258673,52.60254794120001,609.6 -3.1826370117,52.6005634786,609.6 -3.1777377416,52.5988766179,609.6 -3.1725799209,52.59750520539999,609.6 -3.167218132,52.59646374839999,609.6 -3.1617091013,52.595763263,609.6 -3.156111102,52.5954111583,609.6 -3.1504833424,52.5954111583,609.6 -3.1448853432,52.595763263,609.6 -3.1393763124,52.59646374839999,609.6 -3.1340145236,52.59750520539999,609.6 -3.1288567029,52.5988766179,609.6 -3.1239574328,52.6005634786,609.6 -3.1193685771,52.60254794120001,609.6 -3.1151387345,52.6048090084,609.6 -3.111312724599999,52.6073227528,609.6 -3.1079311144,52.61006256870001,609.6 -3.1050297872,52.6129994526,609.6 -3.102639561200001,52.61610230880001,609.6 -3.1007858596,52.6193382778,609.6 -3.0994884379,52.6226730826,609.6 -3.0987611698,52.6260713921,609.6 -3.0986118953,52.6294971935,609.6 -3.0990423317,52.6329141749,609.6 -3.1000480499,52.6362861091,609.6 -3.1016185159,52.6395772385,609.6 -3.1037371966,52.6427526543,609.6 -3.1063817306,52.64577866800001,609.6 -3.109524161,52.6486231691,609.6 -3.1131312286,52.6512559674,609.6 -3.1171647219,52.65364911429999,609.6 -3.1215818817,52.65577720109999,609.6 -3.1263358541,52.6576176296,609.6 -3.1313761886,52.6591508538,609.6 -3.136649375,52.6603605885,609.6 -3.1420994145,52.661233983,609.6 -3.1476684176,52.66176175910001,609.6 -3.1532972222,52.6619383097,609.6 + + + + +
+ + EGRU202B WELSHPOOL RWY 04 + 523510N 0031134W -
523529N 0031218W -
523615N 0031125W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to
523556N 0031041W -
523510N 0031134W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1928166667,52.5861333333,609.6 -3.1781366111,52.5989991389,609.6 -3.1824262144,52.6004823189,609.6 -3.186479086,52.6021947615,609.6 -3.19026225,52.6041225556,609.6 -3.2049305556,52.5912638889,609.6 -3.1928166667,52.5861333333,609.6 + + + + +
+ + EGRU202C WELSHPOOL RWY 22 + 524016N 0030650W -
523957N 0030606W -
523911N 0030658W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to
523930N 0030742W -
524016N 0030650W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1138,52.67099999999999,609.6 -3.1283630833,52.65828202780001,609.6 -3.1240726758,52.6567936288,609.6 -3.1200207057,52.6550759558,609.6 -3.1162401944,52.6531430278,609.6 -3.1016638889,52.6658694444,609.6 -3.1138,52.67099999999999,609.6 + + + + +
+ + EGRU203A SHOBDON + A circle, 2 NM radius, centred at 521430N 0025252W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8811111111,52.2749543894,609.6 -2.8866907656,52.274777829,609.6 -2.892211142599999,52.27425002369999,609.6 -2.8976135985,52.2733765806,609.6 -2.9028407506,52.2721667782,609.6 -2.9078370904,52.2706334675,609.6 -2.9125495762,52.2687929342,609.6 -2.9169281982,52.26666472489999,609.6 -2.9209265119,52.2642714384,609.6 -2.9245021309,52.2616384845,609.6 -2.9276171767,52.2587938129,609.6 -2.9302386792,52.255767615,609.6 -2.9323389239,52.2525920027,609.6 -2.9338957425,52.2493006663,609.6 -2.9348927443,52.2459285165,609.6 -2.9353194846,52.2425113129,609.6 -2.935171570500001,52.23908528490001,609.6 -2.934450702,52.23568674720001,609.6 -2.9331646481,52.2323517147,609.6 -2.9313271595,52.2291155216,609.6 -2.9289578173,52.2260124472,609.6 -2.9260818216,52.22307535400001,609.6 -2.9227297205,52.2203353404,609.6 -2.918937083699999,52.2178214126,609.6 -2.9147441241,52.2155601787,609.6 -2.910195271,52.2135755685,609.6 -2.9053386998,52.2118885813,609.6 -2.9002258233,52.2105170653,609.6 -2.8949107497,52.2094755293,609.6 -2.8894497124,52.20877499060001,609.6 -2.8839004789,52.208422859,609.6 -2.8783217433,52.208422859,609.6 -2.872772509899999,52.20877499060001,609.6 -2.8673114726,52.2094755293,609.6 -2.8619963989,52.2105170653,609.6 -2.8568835225,52.2118885813,609.6 -2.8520269513,52.2135755685,609.6 -2.847478098099999,52.2155601787,609.6 -2.8432851385,52.2178214126,609.6 -2.8394925017,52.2203353404,609.6 -2.8361404006,52.22307535400001,609.6 -2.8332644049,52.2260124472,609.6 -2.8308950627,52.2291155216,609.6 -2.8290575741,52.2323517147,609.6 -2.8277715202,52.23568674720001,609.6 -2.8270506517,52.23908528490001,609.6 -2.826902737600001,52.2425113129,609.6 -2.827329477900001,52.2459285165,609.6 -2.8283264797,52.2493006663,609.6 -2.8298832984,52.2525920027,609.6 -2.831983543,52.255767615,609.6 -2.8346050455,52.2587938129,609.6 -2.8377200913,52.2616384845,609.6 -2.8412957103,52.2642714384,609.6 -2.845294024,52.26666472489999,609.6 -2.8496726461,52.2687929342,609.6 -2.8543851318,52.2706334675,609.6 -2.8593814716,52.2721667782,609.6 -2.8646086238,52.2733765806,609.6 -2.8700110796,52.27425002369999,609.6 -2.875531456600001,52.274777829,609.6 -2.8811111111,52.2749543894,609.6 + + + + +
+ + EGRU203B SHOBDON RWY 08 + 521352N 0025732W -
521424N 0025739W -
521431N 0025607W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to
521359N 0025600W -
521352N 0025732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9589777778,52.2310055556,609.6 -2.9334707778,52.2330216667,609.6 -2.9345288123,52.23595499950001,609.6 -2.9351518764,52.2389349498,609.6 -2.935334805600001,52.24193724999999,609.6 -2.9608333333,52.2399222222,609.6 -2.9589777778,52.2310055556,609.6 + + + + +
+ + EGRU203C SHOBDON RWY 26 + 521508N 0024813W -
521436N 0024806W -
521429N 0024937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to
521501N 0024943W -
521508N 0024813W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.803475,52.2522666667,609.6 -2.828736000000001,52.2502995833,609.6 -2.8276831046,52.2473661174,609.6 -2.8270654286,52.2443863328,609.6 -2.8268879167,52.2413845,609.6 -2.8016166667,52.2433527778,609.6 -2.803475,52.2522666667,609.6 + + + + +
+ + EGRU204A SLEAP + A circle, 2 NM radius, centred at 525002N 0024618W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7716666667,52.8671732622,609.6 -2.7773219972,52.8669967167,609.6 -2.7829172434,52.86646895609999,609.6 -2.7883929636,52.8655955872,609.6 -2.7936909943,52.86438588819999,609.6 -2.7987550722,52.8628527096,609.6 -2.8035314345,52.8610123364,609.6 -2.8079693927,52.8588843143,609.6 -2.8120218721,52.8564912409,609.6 -2.815645911899999,52.8538585248,609.6 -2.8188031213,52.8510141137,609.6 -2.8214600849,52.8479881974,609.6 -2.8235887151,52.8448128853,609.6 -2.8251665461,52.84152186539999,609.6 -2.8261769682,52.8381500451,609.6 -2.8266093991,52.83473318120001,609.6 -2.82645939,52.8313074995,609.6 -2.8257286679,52.8279093109,609.6 -2.8244251109,52.8245746265,609.6 -2.8225626591,52.8213387762,609.6 -2.8201611621,52.81823603550001,609.6 -2.8172461638,52.8152992624,609.6 -2.8138486278,52.8125595511,609.6 -2.8100046069,52.8100459039,609.6 -2.805754859,52.807784925,609.6 -2.8011444147,52.80580054070001,609.6 -2.7962221007,52.8041137471,609.6 -2.7910400244,52.8027423894,609.6 -2.7856530242,52.8017009742,609.6 -2.7801180923,52.8010005171,609.6 -2.7744937751,52.80064842670001,609.6 -2.7688395582,52.80064842670001,609.6 -2.763215241,52.8010005171,609.6 -2.7576803091,52.8017009742,609.6 -2.7522933089,52.8027423894,609.6 -2.7471112326,52.8041137471,609.6 -2.7421889187,52.80580054070001,609.6 -2.7375784743,52.807784925,609.6 -2.7333287264,52.8100459039,609.6 -2.7294847055,52.8125595511,609.6 -2.7260871695,52.8152992624,609.6 -2.7231721712,52.81823603550001,609.6 -2.7207706742,52.8213387762,609.6 -2.7189082225,52.8245746265,609.6 -2.7176046654,52.8279093109,609.6 -2.7168739433,52.8313074995,609.6 -2.7167239343,52.83473318120001,609.6 -2.7171563651,52.8381500451,609.6 -2.7181667872,52.84152186539999,609.6 -2.7197446182,52.8448128853,609.6 -2.7218732484,52.8479881974,609.6 -2.7245302121,52.8510141137,609.6 -2.7276874215,52.8538585248,609.6 -2.7313114613,52.8564912409,609.6 -2.7353639406,52.8588843143,609.6 -2.7398018988,52.8610123364,609.6 -2.7445782612,52.8628527096,609.6 -2.7496423391,52.86438588819999,609.6 -2.7549403698,52.8655955872,609.6 -2.7604160899,52.86646895609999,609.6 -2.7660113361,52.8669967167,609.6 -2.7716666667,52.8671732622,609.6 + + + + +
+ + EGRU204B SLEAP RWY 05 + 524748N 0024923W -
524811N 0025001W -
524850N 0024856W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
524827N 0024818W -
524748N 0024923W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.823030555599999,52.796675,609.6 -2.8051105556,52.80748088890001,609.6 -2.8089038559,52.8094142415,609.6 -2.8123944447,52.81154682439999,609.6 -2.815553888899999,52.8138613056,609.6 -2.8334805556,52.80305,609.6 -2.823030555599999,52.796675,609.6 + + + + +
+ + EGRU204C SLEAP RWY 23 + 525217N 0024311W -
525154N 0024234W -
525114N 0024340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
525137N 0024418W -
525217N 0024311W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7198416667,52.8714472222,609.6 -2.7383165278,52.86034961109999,609.6 -2.7345122636,52.8584212007,609.6 -2.7310110402,52.8562929696,609.6 -2.7278413611,52.8539822778,609.6 -2.7093722222,52.865075,609.6 -2.7198416667,52.8714472222,609.6 + + + + +
+ + EGRU204D SLEAP RWY 18 + 525253N 0024646W -
525253N 0024553W -
525201N 0024551W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
525201N 0024644W -
525253N 0024646W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7795583333,52.88128333329999,609.6 -2.7789823611,52.8668773056,609.6 -2.7740367547,52.8671423114,609.6 -2.7690717949,52.8671361609,609.6 -2.7641280278,52.8668588889,609.6 -2.7647083333,52.8815,609.6 -2.7795583333,52.88128333329999,609.6 + + + + +
+ + EGRU204E SLEAP RWY 36 + 524705N 0024539W -
524704N 0024633W -
524803N 0024635W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
524804N 0024542W -
524705N 0024539W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7608805556,52.7847416667,609.6 -2.7615295,52.8011758333,609.6 -2.7664380394,52.8007554016,609.6 -2.7713890858,52.80060474379999,609.6 -2.7763423889,52.8007250833,609.6 -2.7756972222,52.7845277778,609.6 -2.7608805556,52.7847416667,609.6 + + + + +
+ + EGRU205A SHAWBURY + A circle, 2 NM radius, centred at 524737N 0024005W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6679388889,52.8269096004,609.6 -2.67358899,52.8267330539,609.6 -2.6791790626,52.8262052903,609.6 -2.6846497199,52.8253319163,609.6 -2.6899428528,52.8241222104,609.6 -2.6950022498,52.8225890229,609.6 -2.6997741981,52.82074863879999,609.6 -2.7042080561,52.818620604,609.6 -2.7082567924,52.8162275163,609.6 -2.7118774863,52.81359478400001,609.6 -2.7150317821,52.8107503553,609.6 -2.7176862954,52.80772441989999,609.6 -2.7198129641,52.80454908750001,609.6 -2.7213893431,52.8012580461,609.6 -2.7223988379,52.7978862036,609.6 -2.7228308756,52.7944693166,609.6 -2.7226810114,52.7910436115,609.6 -2.7219509703,52.7876453991,609.6 -2.7206486227,52.7843106911,609.6 -2.718787896,52.7810748176,609.6 -2.716388621,52.7779720542,609.6 -2.7134763179,52.7750352593,609.6 -2.7100819216,52.7722955276,609.6 -2.7062414514,52.7697818613,609.6 -2.7019956277,52.7675208651,609.6 -2.6973894394,52.7655364654,609.6 -2.6924716684,52.7638496586,609.6 -2.6872943739,52.76247829019999,609.6 -2.6819123439,52.7614368668,609.6 -2.6763825182,52.76073640420001,609.6 -2.6707633894,52.7603843109,609.6 -2.6651143884,52.7603843109,609.6 -2.6594952596,52.76073640420001,609.6 -2.6539654339,52.7614368668,609.6 -2.6485834039,52.76247829019999,609.6 -2.6434061094,52.7638496586,609.6 -2.6384883384,52.7655364654,609.6 -2.6338821501,52.7675208651,609.6 -2.6296363263,52.7697818613,609.6 -2.6257958562,52.7722955276,609.6 -2.6224014599,52.7750352593,609.6 -2.6194891568,52.7779720542,609.6 -2.6170898818,52.7810748176,609.6 -2.615229155,52.7843106911,609.6 -2.6139268075,52.7876453991,609.6 -2.6131967664,52.7910436115,609.6 -2.6130469022,52.7944693166,609.6 -2.6134789398,52.7978862036,609.6 -2.6144884347,52.8012580461,609.6 -2.6160648137,52.80454908750001,609.6 -2.6181914824,52.80772441989999,609.6 -2.6208459957,52.8107503553,609.6 -2.6240002915,52.81359478400001,609.6 -2.6276209853,52.8162275163,609.6 -2.6316697217,52.818620604,609.6 -2.6361035797,52.82074863879999,609.6 -2.640875528,52.8225890229,609.6 -2.645934925,52.8241222104,609.6 -2.6512280578,52.8253319163,609.6 -2.6566987152,52.8262052903,609.6 -2.6622887877,52.8267330539,609.6 -2.6679388889,52.8269096004,609.6 + + + + +
+ + EGRU205B SHAWBURY RWY 05 + 524527N 0024325W -
524550N 0024403W -
524633N 0024252W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524609N 0024218W -
524527N 0024325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7235820278,52.7576245833,609.6 -2.7049352778,52.76903544439999,609.6 -2.7084554449,52.7711671052,609.6 -2.7116432321,52.7734832474,609.6 -2.7144724444,52.7759648611,609.6 -2.7340958611,52.7639548056,609.6 -2.7235820278,52.7576245833,609.6 + + + + +
+ + EGRU205C SHAWBURY RWY 23 + 525011N 0023655W -
524949N 0023617W -
524858N 0023740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524919N 0023821W -
525011N 0023655W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6153044722,52.8365074722,609.6 -2.6391511389,52.82197188890001,609.6 -2.6350330637,52.82027527139999,609.6 -2.631185824,52.8183596115,609.6 -2.6276410556,52.8162406667,609.6 -2.6047731389,52.8301773333,609.6 -2.6153044722,52.8365074722,609.6 + + + + +
+ + EGRU205D SHAWBURY RWY 18 + 525048N 0024032W -
525048N 0023939W -
524936N 0023938W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524936N 0024032W -
525048N 0024032W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6755396111,52.84677375,609.6 -2.6754679167,52.8265954444,609.6 -2.6705304301,52.826872528,609.6 -2.6655717917,52.8268786728,609.6 -2.6606324722,52.8266138333,609.6 -2.6606972778,52.8467921389,609.6 -2.6755396111,52.84677375,609.6 + + + + +
+ + EGRU205E SHAWBURY RWY 36 + 524426N 0023937W -
524426N 0024031W -
524538N 0024031W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524538N 0023938W -
524426N 0023937W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6603565556,52.7404752778,609.6 -2.6604210833,52.7606538889,609.6 -2.6653511557,52.76037723659999,609.6 -2.6703022476,52.76037109369999,609.6 -2.6752341389,52.76063552779999,609.6 -2.6751627778,52.7404568889,609.6 -2.6603565556,52.7404752778,609.6 + + + + +
+ + EGRU206A TERNHILL + A circle, 2 NM radius, centred at 525223N 0023156W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5321916667,52.90644526289999,609.6 -2.5378521099,52.90626871849999,609.6 -2.5434524143,52.9057409608,609.6 -2.5489330842,52.9048675968,609.6 -2.5542359034,52.9036579047,609.6 -2.5593045577,52.9021247347,609.6 -2.5640852355,52.9002843721,609.6 -2.5685272025,52.8981563623,609.6 -2.5725833412,52.895763303,609.6 -2.5762106523,52.89313060250001,609.6 -2.5793707102,52.8902862087,609.6 -2.5820300695,52.8872603109,609.6 -2.5841606174,52.8840850187,609.6 -2.5857398679,52.8807940196,609.6 -2.5867511966,52.8774222212,609.6 -2.5871840119,52.8740053798,609.6 -2.5870338612,52.87057972099999,609.6 -2.5863024734,52.8671815554,609.6 -2.5849977337,52.86384689400001,609.6 -2.5831335954,52.86061106649999,609.6 -2.5807299261,52.8575083478,609.6 -2.5778122927,52.8545715958,609.6 -2.5744116872,52.8518319046,609.6 -2.5705641948,52.849318276,609.6 -2.5663106103,52.847057314,609.6 -2.5616960049,52.8450729446,609.6 -2.5567692495,52.8433861638,609.6 -2.5515824981,52.8420148166,609.6 -2.5461906387,52.84097340949999,609.6 -2.5406507145,52.8402729578,609.6 -2.5350213248,52.8399208701,609.6 -2.5293620085,52.8399208701,609.6 -2.5237326188,52.8402729578,609.6 -2.5181926947,52.84097340949999,609.6 -2.5128008352,52.8420148166,609.6 -2.5076140839,52.8433861638,609.6 -2.5026873284,52.8450729446,609.6 -2.498072723,52.847057314,609.6 -2.4938191385,52.849318276,609.6 -2.4899716461,52.8518319046,609.6 -2.4865710406,52.8545715958,609.6 -2.4836534073,52.8575083478,609.6 -2.4812497379,52.86061106649999,609.6 -2.4793855996,52.86384689400001,609.6 -2.47808086,52.8671815554,609.6 -2.4773494721,52.87057972099999,609.6 -2.4771993215,52.8740053798,609.6 -2.4776321367,52.8774222212,609.6 -2.4786434655,52.8807940196,609.6 -2.480222716,52.8840850187,609.6 -2.4823532638,52.8872603109,609.6 -2.4850126232,52.8902862087,609.6 -2.4881726811,52.89313060250001,609.6 -2.4917999922,52.895763303,609.6 -2.4958561309,52.8981563623,609.6 -2.5002980978,52.9002843721,609.6 -2.5050787756,52.9021247347,609.6 -2.5101474299,52.9036579047,609.6 -2.5154502492,52.9048675968,609.6 -2.520930919,52.9057409608,609.6 -2.5265312234,52.90626871849999,609.6 -2.5321916667,52.90644526289999,609.6 + + + + +
+ + EGRU206B TERNHILL RWY 04 + 525004N 0023450W -
525026N 0023529W -
525107N 0023428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525045N 0023348W -
525004N 0023450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5805501389,52.8343893333,609.6 -2.5634260556,52.8457666667,609.6 -2.5673785486,52.847581813,609.6 -2.5710450266,52.8496051651,609.6 -2.5743956389,52.8518202778,609.6 -2.5915122222,52.8404460278,609.6 -2.5805501389,52.8343893333,609.6 + + + + +
+ + EGRU206C TERNHILL RWY 22 + 525443N 0022902W -
525421N 0022822W -
525340N 0022924W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525402N 0023003W -
525443N 0022902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4837607222,52.9119084722,609.6 -2.5009221944,52.900549,609.6 -2.4969673837,52.89873187969999,609.6 -2.4932998953,52.8967064683,609.6 -2.4899496111,52.89448927780001,609.6 -2.4727806111,52.9058518611,609.6 -2.4837607222,52.9119084722,609.6 + + + + +
+ + EGRU206D TERNHILL RWY 10 + 525233N 0023651W -
525305N 0023643W -
525256N 0023506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525224N 0023514W -
525233N 0023651W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6141188611,52.8759196389,609.6 -2.5872000556,52.87338677779999,609.6 -2.5869443115,52.876386522,609.6 -2.5862425569,52.87936009700001,609.6 -2.5851004167,52.88228327779999,609.6 -2.6118228056,52.8847976389,609.6 -2.6141188611,52.8759196389,609.6 + + + + +
+ + EGRU206E TERNHILL RWY 28 + 525212N 0022717W -
525140N 0022725W -
525148N 0022847W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525219N 0022838W -
525212N 0022717W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4546785556,52.8699211389,609.6 -2.4772125278,52.8720677778,609.6 -2.4776011819,52.8690732605,609.6 -2.4784342929,52.8661121323,609.6 -2.479705,52.8632085,609.6 -2.4569738333,52.8610431111,609.6 -2.4546785556,52.8699211389,609.6 + + + + +
+ + EGRU206F TERNHILL RWY 17 + 525513N 0023310W -
525520N 0023217W -
525423N 0023159W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525418N 0023252W -
525513N 0023310W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5527453056,52.9203575,609.6 -2.547651,52.90510488889999,609.6 -2.5428192861,52.9058186705,609.6 -2.5379006231,52.90626566900001,609.6 -2.53293525,52.90644222219999,609.6 -2.5381707222,52.92213338890001,609.6 -2.5527453056,52.9203575,609.6 + + + + +
+ + EGRU206G TERNHILL RWY 35 + 524937N 0023023W -
524931N 0023116W -
525024N 0023134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525032N 0023042W -
524937N 0023023W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.50649125,52.8270092778,609.6 -2.5115754722,52.8423044722,609.6 -2.5162593978,52.84130443,609.6 -2.5210730991,52.84056426330001,609.6 -2.5259773611,52.84009,609.6 -2.521034,52.8252333889,609.6 -2.50649125,52.8270092778,609.6 + + + + +
+ + EGRU207A COSFORD + A circle, 2 NM radius, centred at 523826N 0021819W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3052,52.6737854649,609.6 -2.3108303271,52.6736089147,609.6 -2.3164008364,52.6730811395,609.6 -2.3218523499,52.67220774639999,609.6 -2.3271269622,52.6709980139,609.6 -2.3321686594,52.6694647923,609.6 -2.3369239169,52.6676243669,609.6 -2.3413422704,52.6654962839,609.6 -2.3453768535,52.66310314119999,609.6 -2.3489848951,52.6604703477,609.6 -2.3521281738,52.6576258518,609.6 -2.3547734212,52.65459984369999,609.6 -2.356892673,52.6514244339,609.6 -2.3584635616,52.6481333109,609.6 -2.3594695499,52.64476138319999,609.6 -2.3599001008,52.6413444087,609.6 -2.3597507841,52.6379186141,609.6 -2.3590233178,52.63452031169999,609.6 -2.3577255439,52.6311855137,609.6 -2.3558713401,52.6279495517,609.6 -2.3534804672,52.6248467021,609.6 -2.3505783554,52.6219098246,609.6 -2.3471958311,52.6191700147,609.6 -2.3433687875,52.6166562759,609.6 -2.3391378023,52.61439521379999,609.6 -2.3345477076,52.6124107558,609.6 -2.3296471149,52.610723899,609.6 -2.3244879021,52.6093524896,609.6 -2.3191246662,52.608311035,609.6 -2.3136141488,52.60761055130001,609.6 -2.3080146391,52.6072584474,609.6 -2.3023853609,52.6072584474,609.6 -2.2967858512,52.60761055130001,609.6 -2.2912753338,52.608311035,609.6 -2.2859120979,52.6093524896,609.6 -2.2807528851,52.610723899,609.6 -2.2758522924,52.6124107558,609.6 -2.2712621977,52.61439521379999,609.6 -2.2670312125,52.6166562759,609.6 -2.2632041689,52.6191700147,609.6 -2.2598216446,52.6219098246,609.6 -2.2569195328,52.6248467021,609.6 -2.2545286599,52.6279495517,609.6 -2.2526744561,52.6311855137,609.6 -2.2513766822,52.63452031169999,609.6 -2.2506492159,52.6379186141,609.6 -2.2504998992,52.6413444087,609.6 -2.2509304501,52.64476138319999,609.6 -2.2519364384,52.6481333109,609.6 -2.253507327,52.6514244339,609.6 -2.2556265788,52.65459984369999,609.6 -2.2582718262,52.6576258518,609.6 -2.2614151049,52.6604703477,609.6 -2.2650231465,52.66310314119999,609.6 -2.2690577296,52.6654962839,609.6 -2.2734760831,52.6676243669,609.6 -2.2782313406,52.6694647923,609.6 -2.2832730378,52.6709980139,609.6 -2.2885476501,52.67220774639999,609.6 -2.2939991636,52.6730811395,609.6 -2.2995696729,52.6736089147,609.6 -2.3052,52.6737854649,609.6 + + + + +
+ + EGRU207B COSFORD RWY 06 + 523637N 0022215W -
523704N 0022243W -
523737N 0022118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523709N 0022050W -
523637N 0022215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3708121389,52.6102927222,609.6 -2.3473025278,52.619248,609.6 -2.3502802235,52.6216433353,609.6 -2.3528913183,52.62419221599999,609.6 -2.3551145,52.62687391669999,609.6 -2.3786348056,52.6179139722,609.6 -2.3708121389,52.6102927222,609.6 + + + + +
+ + EGRU207C COSFORD RWY 24 + 524015N 0021423W -
523947N 0021355W -
523915N 0021519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523943N 0021547W -
524015N 0021423W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2396455556,52.6707405556,609.6 -2.26317,52.6618198889,609.6 -2.2601815668,52.6594282563,609.6 -2.2575601865,52.65688249580001,609.6 -2.2553271667,52.6542033611,609.6 -2.2318134444,52.6631193889,609.6 -2.2396455556,52.6707405556,609.6 + + + + +
+ + EGRU207D COSFORD RWY 06L + 523639N 0022217W -
523707N 0022245W -
523739N 0022120W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523711N 0022053W -
523639N 0022217W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3714746389,52.6108995278,609.6 -2.3480534722,52.6198109722,609.6 -2.3509455268,52.6222458531,609.6 -2.3534653466,52.6248294636,609.6 -2.3555923611,52.62754077779999,609.6 -2.3792911389,52.6185231667,609.6 -2.3714746389,52.6108995278,609.6 + + + + +
+ + EGRU207E COSFORD RWY 24R + 524016N 0021428W -
523948N 0021359W -
523917N 0021521W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523944N 0021550W -
524016N 0021428W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2410140556,52.67101977780001,609.6 -2.2639089722,52.6623476389,609.6 -2.260838454,52.6599937279,609.6 -2.2581298286,52.6574809994,609.6 -2.2558051389,52.6548299444,609.6 -2.2331881944,52.6633962222,609.6 -2.2410140556,52.67101977780001,609.6 + + + + +
+ + EGRU208A WOLVERHAMPTON/HALFPENNY GREEN + A circle, 2 NM radius, centred at 523103N 0021534W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2595472222,52.5506694943,609.6 -2.2651617798,52.550492941,609.6 -2.2707166877,52.54996515649999,609.6 -2.2761529343,52.549091748,609.6 -2.2814127768,52.54788199399999,609.6 -2.2864403587,52.5463487449,609.6 -2.2911823054,52.5445082863,609.6 -2.2955882944,52.5423801644,609.6 -2.2996115904,52.5399869775,609.6 -2.303209542,52.5373541345,609.6 -2.3063440346,52.5345095845,609.6 -2.3089818926,52.53148351789999,609.6 -2.3110952293,52.52830804570001,609.6 -2.3126617395,52.5250168569,609.6 -2.3136649312,52.5216448608,609.6 -2.3140942963,52.51822781570001,609.6 -2.3139454162,52.5148019491,609.6 -2.3132200032,52.5114035741,609.6 -2.3119258767,52.50806870390001,609.6 -2.3100768748,52.5048326706,609.6 -2.3076927023,52.5017297516,609.6 -2.3047987179,52.4987928076,609.6 -2.3014256614,52.4960529349,609.6 -2.2976093253,52.4935391378,609.6 -2.2933901738,52.49127802269999,609.6 -2.2888129135,52.4892935177,609.6 -2.2839260204,52.4876066206,609.6 -2.2787812274,52.48623517840001,609.6 -2.2734329797,52.4851936987,609.6 -2.2679378606,52.484493198,609.6 -2.2623539968,52.4841410855,609.6 -2.2567404476,52.4841410855,609.6 -2.2511565839,52.484493198,609.6 -2.2456614647,52.4851936987,609.6 -2.240313217,52.48623517840001,609.6 -2.2351684241,52.4876066206,609.6 -2.2302815309,52.4892935177,609.6 -2.2257042707,52.49127802269999,609.6 -2.2214851191,52.4935391378,609.6 -2.217668783,52.4960529349,609.6 -2.2142957265,52.4987928076,609.6 -2.2114017421,52.5017297516,609.6 -2.2090175697,52.5048326706,609.6 -2.2071685677,52.50806870390001,609.6 -2.2058744412,52.5114035741,609.6 -2.2051490283,52.5148019491,609.6 -2.2050001482,52.51822781570001,609.6 -2.2054295133,52.5216448608,609.6 -2.206432705,52.5250168569,609.6 -2.2079992151,52.52830804570001,609.6 -2.2101125519,52.53148351789999,609.6 -2.2127504099,52.5345095845,609.6 -2.2158849024,52.5373541345,609.6 -2.2194828541,52.5399869775,609.6 -2.22350615,52.5423801644,609.6 -2.227912139,52.5445082863,609.6 -2.2326540858,52.5463487449,609.6 -2.2376816676,52.54788199399999,609.6 -2.2429415102,52.549091748,609.6 -2.2483777568,52.54996515649999,609.6 -2.2539326647,52.550492941,609.6 -2.2595472222,52.5506694943,609.6 + + + + +
+ + EGRU208B WOLVERHAMPTON/HALFPENNY GREEN RWY 04 + 522840N 0021816W -
522859N 0021859W -
522945N 0021803W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
522923N 0021724W -
522840N 0021816W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3045555556,52.4777166667,609.6 -2.2899011667,52.4897268611,609.6 -2.2938762625,52.49151540919999,609.6 -2.2975703338,52.4935160039,609.6 -2.3009530833,52.4957122778,609.6 -2.3163527778,52.4830888889,609.6 -2.3045555556,52.4777166667,609.6 + + + + +
+ + EGRU208C WOLVERHAMPTON/HALFPENNY GREEN RWY 22 + 523332N 0021326W -
523313N 0021243W -
523235N 0021329W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
523252N 0021414W -
523332N 0021326W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2237694444,52.5588416667,609.6 -2.2373114444,52.5477822778,609.6 -2.2328922036,52.5464304954,609.6 -2.2286919692,52.54484039,609.6 -2.2247452222,52.5430250278,609.6 -2.21195,52.55347222220001,609.6 -2.2237694444,52.5588416667,609.6 + + + + +
+ + EGRU208D WOLVERHAMPTON/HALFPENNY GREEN RWY 16 + 523335N 0021755W -
523348N 0021707W -
523258N 0021630W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
523244N 0021718W -
523335N 0021755W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2987055556,52.5595916667,609.6 -2.2884155278,52.54563275,609.6 -2.2841209325,52.5471052761,609.6 -2.2796258124,52.5483356141,609.6 -2.2749668333,52.54931372219999,609.6 -2.28525,52.5632694444,609.6 -2.2987055556,52.5595916667,609.6 + + + + +
+ + EGRU208E WOLVERHAMPTON/HALFPENNY GREEN RWY 34 + 522830N 0021313W -
522816N 0021401W -
522908N 0021439W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
522921N 0021351W -
522830N 0021313W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2202611111,52.4749055556,609.6 -2.2307041944,52.4891311944,609.6 -2.2349940211,52.4876600186,609.6 -2.2394833707,52.48643072530001,609.6 -2.24413575,52.48545330559999,609.6 -2.2336861111,52.471225,609.6 -2.2202611111,52.4749055556,609.6 + + + + +
+ + EGRU209A TATENHILL + A circle, 2 NM radius, centred at 524851N 0014553W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7647083333,52.84735392950001,609.6 -1.7703610882,52.8471773836,609.6 -1.7759537862,52.8466496214,609.6 -1.7814270127,52.8457762501,609.6 -1.786722631,52.8445665477,609.6 -1.7917844034,52.8430333647,609.6 -1.7965585917,52.8411929861,609.6 -1.8009945304,52.8390649577,609.6 -1.8050451662,52.8366718773,609.6 -1.808667558,52.8340391532,609.6 -1.8118233323,52.8311947335,609.6 -1.8144790891,52.8281688078,609.6 -1.8166067531,52.82499348569999,609.6 -1.818183869,52.8217024552,609.6 -1.8191938344,52.818330624,609.6 -1.8196260716,52.81491374880001,609.6 -1.8194761339,52.8114880555,609.6 -1.8187457472,52.8080898552,609.6 -1.8174427859,52.8047551592,609.6 -1.8155811838,52.8015192975,609.6 -1.8131807812,52.7984165455,609.6 -1.8102671103,52.79547976170001,609.6 -1.8068711208,52.7927400404,609.6 -1.8030288488,52.7902263838,609.6 -1.7987810336,52.7879653964,609.6 -1.7941726856,52.78598100450001,609.6 -1.7892526091,52.7842942044,609.6 -1.7840728881,52.7829228414,609.6 -1.7786883359,52.7818814222,609.6 -1.773155919,52.7811809624,609.6 -1.7675341573,52.7808288706,609.6 -1.7618825094,52.7808288706,609.6 -1.7562607477,52.7811809624,609.6 -1.7507283308,52.7818814222,609.6 -1.7453437786,52.7829228414,609.6 -1.7401640575,52.7842942044,609.6 -1.7352439811,52.78598100450001,609.6 -1.730635633,52.7879653964,609.6 -1.7263878179,52.7902263838,609.6 -1.7225455459,52.7927400404,609.6 -1.7191495563,52.79547976170001,609.6 -1.7162358855,52.7984165455,609.6 -1.7138354829,52.8015192975,609.6 -1.7119738808,52.8047551592,609.6 -1.7106709195,52.8080898552,609.6 -1.7099405328,52.8114880555,609.6 -1.7097905951,52.81491374880001,609.6 -1.7102228322,52.818330624,609.6 -1.7112327977,52.8217024552,609.6 -1.7128099135,52.82499348569999,609.6 -1.7149375776,52.8281688078,609.6 -1.7175933343,52.8311947335,609.6 -1.7207491087,52.8340391532,609.6 -1.7243715005,52.8366718773,609.6 -1.7284221363,52.8390649577,609.6 -1.7328580749,52.8411929861,609.6 -1.7376322632,52.8430333647,609.6 -1.7426940356,52.8445665477,609.6 -1.7479896539,52.8457762501,609.6 -1.7534628805,52.8466496214,609.6 -1.7590555784,52.8471773836,609.6 -1.7647083333,52.84735392950001,609.6 + + + + +
+ + EGRU209B TATENHILL RWY 08 + 524744N 0015032W -
524815N 0015047W -
524833N 0014908W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to
524802N 0014853W -
524744N 0015032W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8422166667,52.7956138889,609.6 -1.8148514167,52.8004843611,609.6 -1.8166692181,52.80327779060001,609.6 -1.8180644306,52.80615912030001,609.6 -1.8190256111,52.80910491669999,609.6 -1.8463805556,52.80423611110001,609.6 -1.8422166667,52.7956138889,609.6 + + + + +
+ + EGRU209C TATENHILL RWY 26 + 524957N 0014114W -
524926N 0014059W -
524908N 0014237W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to
524939N 0014252W -
524957N 0014114W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6871555556,52.8324722222,609.6 -1.7145350278,52.8276346944,609.6 -1.7127224882,52.8248396575,609.6 -1.7113333994,52.8219570266,609.6 -1.710379,52.8190102778,609.6 -1.6829861111,52.82384999999999,609.6 -1.6871555556,52.8324722222,609.6 + + + + +
+ + EGRU210A BIRMINGHAM + A circle, 2.5 NM radius, centred at 522722N 0014502W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7505555556,52.4977192163,609.6 -1.7568458982,52.497541557,609.6 -1.763082423,52.4970100989,609.6 -1.7692117761,52.496129389,609.6 -1.7751815286,52.49490696149999,609.6 -1.7809406276,52.4933532735,609.6 -1.7864398366,52.4914816145,609.6 -1.7916321586,52.48930799189999,609.6 -1.7964732401,52.4868509931,609.6 -1.8009217512,52.4841316255,609.6 -1.8049397389,52.4811731357,609.6 -1.8084929515,52.4780008096,609.6 -1.8115511291,52.4746417551,609.6 -1.8140882605,52.4711246695,609.6 -1.8160828021,52.467479593,609.6 -1.8175178582,52.4637376518,609.6 -1.8183813209,52.4599307911,609.6 -1.818665969,52.4560915023,609.6 -1.8183695247,52.4522525448,609.6 -1.8174946675,52.448446667,609.6 -1.8160490067,52.44470632659999,609.6 -1.8140450112,52.4410634144,609.6 -1.8114998987,52.4375489828,609.6 -1.8084354845,52.4341929817,609.6 -1.8048779924,52.4310240045,609.6 -1.8008578279,52.4280690449,609.6 -1.7964093168,52.42535326870001,609.6 -1.7915704121,52.4228998002,609.6 -1.7863823696,52.4207295265,609.6 -1.7808893971,52.4188609209,609.6 -1.7751382792,52.417309887,609.6 -1.7691779807,52.41608962379999,609.6 -1.7630592323,52.4152105147,609.6 -1.756834102,52.4146800394,609.6 -1.7505555556,52.4145027115,609.6 -1.7442770091,52.4146800394,609.6 -1.7380518788,52.4152105147,609.6 -1.7319331305,52.41608962379999,609.6 -1.7259728319,52.417309887,609.6 -1.720221714,52.4188609209,609.6 -1.7147287415,52.4207295265,609.6 -1.709540699,52.4228998002,609.6 -1.7047017943,52.42535326870001,609.6 -1.7002532833,52.4280690449,609.6 -1.6962331187,52.4310240045,609.6 -1.6926756266,52.4341929817,609.6 -1.6896112124,52.4375489828,609.6 -1.6870660999,52.4410634144,609.6 -1.6850621044,52.44470632659999,609.6 -1.6836164436,52.448446667,609.6 -1.6827415864,52.4522525448,609.6 -1.6824451421,52.4560915023,609.6 -1.6827297903,52.4599307911,609.6 -1.6835932529,52.4637376518,609.6 -1.685028309,52.467479593,609.6 -1.6870228506,52.4711246695,609.6 -1.689559982,52.4746417551,609.6 -1.6926181596,52.4780008096,609.6 -1.6961713722,52.4811731357,609.6 -1.7001893599,52.4841316255,609.6 -1.704637871,52.4868509931,609.6 -1.7094789525,52.48930799189999,609.6 -1.7146712746,52.4914816145,609.6 -1.7201704835,52.4933532735,609.6 -1.7259295825,52.49490696149999,609.6 -1.731899335,52.496129389,609.6 -1.7380286881,52.4970100989,609.6 -1.7442652129,52.497541557,609.6 -1.7505555556,52.4977192163,609.6 + + + + +
+ + EGRU210B BIRMINGHAM RWY 15 + 522953N 0014822W -
523011N 0014738W -
522934N 0014657W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to
522916N 0014741W -
522953N 0014822W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8062,52.4981111111,609.6 -1.7947085,52.48780075,609.6 -1.7908524655,52.48966253650001,609.6 -1.7867862897,52.4913496605,609.6 -1.7825311667,52.4928533333,609.6 -1.7940166667,52.50316111109999,609.6 -1.8062,52.4981111111,609.6 + + + + +
+ + EGRU210C BIRMINGHAM RWY 33 + 522442N 0014132W -
522424N 0014216W -
522510N 0014307W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to
522528N 0014223W -
522442N 0014132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6922444444,52.41161666669999,609.6 -1.7064432222,52.4244166667,609.6 -1.7102953441,52.42255677090001,609.6 -1.7143564184,52.4208713218,609.6 -1.7186053333,52.4193690556,609.6 -1.7044,52.4065666667,609.6 -1.6922444444,52.41161666669999,609.6 + + + + +
+ + EGRU211A DERBY + A circle, 2 NM radius, centred at 525135N 0013703W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6175,52.89300644979999,609.6 -1.6231586924,52.89282990499999,609.6 -1.6287572645,52.89230214629999,609.6 -1.6342362393,52.8914287806,609.6 -1.6395374187,52.89021908620001,609.6 -1.6446045057,52.88868591330001,609.6 -1.6493837057,52.886845547,609.6 -1.6538242998,52.884717533,609.6 -1.6578791853,52.88232446890001,609.6 -1.6615053761,52.8796917631,609.6 -1.6646644585,52.87684736330001,609.6 -1.6673229974,52.8738214592,609.6 -1.6694528885,52.8706461602,609.6 -1.6710316529,52.867355154,609.6 -1.6720426712,52.8639833481,609.6 -1.6724753548,52.860566499,609.6 -1.6723252526,52.8571408323,609.6 -1.6715940928,52.8537426589,609.6 -1.6702897581,52.8504079896,609.6 -1.6684261974,52.8471721543,609.6 -1.666023272,52.8440694281,609.6 -1.663106541,52.8411326689,609.6 -1.6597069867,52.8383929708,609.6 -1.6558606832,52.8358793358,609.6 -1.6516084125,52.83361836810001,609.6 -1.6469952321,52.8316339936,609.6 -1.6420699977,52.82994720839999,609.6 -1.6368848474,52.8285758576,609.6 -1.631494652,52.8275344477,609.6 -1.6259564376,52.8268339942,609.6 -1.620328785,52.8264819055,609.6 -1.614671215,52.8264819055,609.6 -1.6090435624,52.8268339942,609.6 -1.603505348,52.8275344477,609.6 -1.5981151526,52.8285758576,609.6 -1.5929300023,52.82994720839999,609.6 -1.5880047679,52.8316339936,609.6 -1.5833915875,52.83361836810001,609.6 -1.5791393168,52.8358793358,609.6 -1.5752930133,52.8383929708,609.6 -1.571893459,52.8411326689,609.6 -1.568976728,52.8440694281,609.6 -1.5665738026,52.8471721543,609.6 -1.5647102419,52.8504079896,609.6 -1.5634059072,52.8537426589,609.6 -1.5626747474,52.8571408323,609.6 -1.5625246452,52.860566499,609.6 -1.5629573288,52.8639833481,609.6 -1.5639683471,52.867355154,609.6 -1.5655471115,52.8706461602,609.6 -1.5676770026,52.8738214592,609.6 -1.5703355415,52.87684736330001,609.6 -1.5734946239,52.8796917631,609.6 -1.5771208147,52.88232446890001,609.6 -1.5811757002,52.884717533,609.6 -1.5856162943,52.886845547,609.6 -1.5903954943,52.88868591330001,609.6 -1.5954625813,52.89021908620001,609.6 -1.6007637607,52.8914287806,609.6 -1.6062427355,52.89230214629999,609.6 -1.6118413076,52.89282990499999,609.6 -1.6175,52.89300644979999,609.6 + + + + +
+ + EGRU211B DERBY RWY 05 + 524927N 0014006W -
524951N 0014042W -
525024N 0013942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525001N 0013905W -
524927N 0014006W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6682780278,52.8241792222,609.6 -1.6514153333,52.8335263333,609.6 -1.6551790821,52.83548432919999,609.6 -1.6586362529,52.8376398054,609.6 -1.6617586667,52.8399752222,609.6 -1.6782875556,52.83081188889999,609.6 -1.6682780278,52.8241792222,609.6 + + + + +
+ + EGRU211C DERBY RWY 23 + 525336N 0013355W -
525312N 0013319W -
525240N 0013417W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525305N 0013452W -
525336N 0013355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5653483889,52.8933006111,609.6 -1.5810313611,52.88464044439999,609.6 -1.5774659925,52.88254823620001,609.6 -1.5742274102,52.8802699556,609.6 -1.571342,52.87782419439999,609.6 -1.5553245,52.886668,609.6 -1.5653483889,52.8933006111,609.6 + + + + +
+ + EGRU211D DERBY RWY 10 + 525144N 0014134W -
525216N 0014126W -
525210N 0014012W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525138N 0014021W -
525144N 0014134W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6926618056,52.86218136109999,609.6 -1.6724770556,52.8605240556,609.6 -1.6721355166,52.8635213229,609.6 -1.6713486888,52.866487734,609.6 -1.6701229167,52.8693991111,609.6 -1.6906521111,52.8710847222,609.6 -1.6926618056,52.86218136109999,609.6 + + + + +
+ + EGRU211E DERBY RWY 28 + 525131N 0013225W -
525059N 0013233W -
525106N 0013351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525138N 0013345W -
525131N 0013225W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5403897778,52.85866194439999,609.6 -1.5625221667,52.86050408330001,609.6 -1.5626315478,52.857500432,609.6 -1.5631879018,52.8545149834,609.6 -1.5641866111,52.8515720556,609.6 -1.5423988889,52.8497585556,609.6 -1.5403897778,52.85866194439999,609.6 + + + + +
+ + EGRU211F DERBY RWY 17 + 525422N 0013812W -
525427N 0013720W -
525335N 0013706W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525330N 0013759W -
525422N 0013812W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.63679225,52.9061841944,609.6 -1.6331029167,52.89163966670001,609.6 -1.6282821584,52.8923609231,609.6 -1.6233734078,52.8928162187,609.6 -1.6184167222,52.8930018333,609.6 -1.6221006389,52.9075444444,609.6 -1.63679225,52.9061841944,609.6 + + + + +
+ + EGRU211G DERBY RWY 35 + 524849N 0013554W -
524844N 0013647W -
524935N 0013700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
524940N 0013607W -
524849N 0013554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5983614722,52.8136583611,609.6 -1.6019306944,52.82780063890001,609.6 -1.6067449988,52.8270810369,609.6 -1.6116466805,52.82662702759999,609.6 -1.6165959167,52.8264423056,609.6 -1.6130214167,52.8122980833,609.6 -1.5983614722,52.8136583611,609.6 + + + + +
+ + EGRU212A WELLESBOURNE MOUNTFORD + A circle, 2 NM radius, centred at 521132N 0013652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6144,52.2254963366,609.6 -1.6199734531,52.225319775,609.6 -1.6254876949,52.2247919659,609.6 -1.6308841471,52.22391851659999,609.6 -1.636105491,52.2227087055,609.6 -1.64109628,52.2211753837,609.6 -1.6458035312,52.21933483690001,609.6 -1.6501772909,52.2172066119,609.6 -1.6541711659,52.2148133076,609.6 -1.6577428169,52.2121803337,609.6 -1.6608544075,52.2093356402,609.6 -1.663473004,52.20630941869999,609.6 -1.6655709225,52.2031337812,609.6 -1.6671260192,52.19984241829999,609.6 -1.6681219212,52.1964702408,609.6 -1.6685481951,52.1930530088,609.6 -1.6684004526,52.1896269519,609.6 -1.6676803914,52.1862283849,609.6 -1.6663957719,52.1828933233,609.6 -1.6645603288,52.1796571014,609.6 -1.6621936216,52.1765539991,609.6 -1.659320822,52.1736168792,609.6 -1.6559724441,52.1708768403,609.6 -1.652184018,52.16836288899999,609.6 -1.6479957121,52.1661016338,609.6 -1.6434519062,52.1641170047,609.6 -1.6386007224,52.1624300014,609.6 -1.6334935167,52.1610584721,609.6 -1.6281843373,52.160016926,609.6 -1.6227293555,52.15931638050001,609.6 -1.617186275,52.15896424549999,609.6 -1.611613725,52.15896424549999,609.6 -1.6060706445,52.15931638050001,609.6 -1.6006156627,52.160016926,609.6 -1.5953064833,52.1610584721,609.6 -1.5901992776,52.1624300014,609.6 -1.5853480938,52.1641170047,609.6 -1.5808042879,52.1661016338,609.6 -1.576615982,52.16836288899999,609.6 -1.5728275559,52.1708768403,609.6 -1.569479178,52.1736168792,609.6 -1.5666063784,52.1765539991,609.6 -1.5642396712,52.1796571014,609.6 -1.5624042281,52.1828933233,609.6 -1.5611196086,52.1862283849,609.6 -1.5603995474,52.1896269519,609.6 -1.5602518049,52.1930530088,609.6 -1.5606780788,52.1964702408,609.6 -1.5616739808,52.19984241829999,609.6 -1.5632290775,52.2031337812,609.6 -1.565326996,52.20630941869999,609.6 -1.5679455925,52.2093356402,609.6 -1.5710571831,52.2121803337,609.6 -1.5746288341,52.2148133076,609.6 -1.5786227091,52.2172066119,609.6 -1.5829964688,52.21933483690001,609.6 -1.58770372,52.2211753837,609.6 -1.592694509,52.2227087055,609.6 -1.5979158529,52.22391851659999,609.6 -1.6033123051,52.2247919659,609.6 -1.6088265469,52.225319775,609.6 -1.6144,52.2254963366,609.6 + + + + +
+ + EGRU212B WELLESBOURNE MOUNTFORD RWY 05 + 520909N 0013952W -
520932N 0014029W -
521014N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
520952N 0013840W -
520909N 0013952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6644833333,52.1525,609.6 -1.6445776111,52.1645690833,609.6 -1.6485160735,52.1663578639,609.6 -1.6521759225,52.1683580392,609.6 -1.6555272222,52.1705532778,609.6 -1.6747361111,52.1589055556,609.6 -1.6644833333,52.1525,609.6 + + + + +
+ + EGRU212C WELLESBOURNE MOUNTFORD RWY 23 + 521332N 0013352W -
521309N 0013315W -
521237N 0013408W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
521302N 0013443W -
521332N 0013352W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5644666667,52.2256444444,609.6 -1.5785241667,52.2171532222,609.6 -1.5750030605,52.2150594228,609.6 -1.5718046369,52.2127787035,609.6 -1.5689550278,52.21032975,609.6 -1.5542,52.2192416667,609.6 -1.5644666667,52.2256444444,609.6 + + + + +
+ + EGRU212D WELLESBOURNE MOUNTFORD RWY 18 + 521427N 0013738W -
521429N 0013645W -
521332N 0013639W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
521329N 0013731W -
521427N 0013738W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6271083333,52.240825,609.6 -1.6253352222,52.22481141670001,609.6 -1.6205050805,52.2252843723,609.6 -1.6156251224,52.22548782689999,609.6 -1.6107351667,52.2254201111,609.6 -1.6125027778,52.24143333329999,609.6 -1.6271083333,52.240825,609.6 + + + + +
+ + EGRU212E WELLESBOURNE MOUNTFORD RWY 36 + 520837N 0013606W -
520835N 0013659W -
520932N 0013705W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
520935N 0013613W -
520837N 0013606W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6017222222,52.1435888889,609.6 -1.6034835,52.1596037222,609.6 -1.6083064442,52.1591316218,609.6 -1.6131788875,52.15892860939999,609.6 -1.61806125,52.1589963333,609.6 -1.6162944444,52.1429805556,609.6 -1.6017222222,52.1435888889,609.6 + + + + +
+ + EGRU213A COVENTRY + A circle, 2.5 NM radius, centred at 522211N 0012847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4796805556,52.41141982709999,609.6 -1.4859586139,52.4112421657,609.6 -1.4921829598,52.41071070140001,609.6 -1.4983003443,52.409829981,609.6 -1.5042584412,52.408607539,609.6 -1.5100062976,52.4070538323,609.6 -1.5154947736,52.40518215070001,609.6 -1.520676964,52.4030085014,609.6 -1.5255086022,52.40055147210001,609.6 -1.5299484387,52.3978320702,609.6 -1.5339585949,52.3948735425,609.6 -1.5375048854,52.3917011751,609.6 -1.5405571093,52.38834207600001,609.6 -1.5430893058,52.3848249429,609.6 -1.5450799728,52.38117981629999,609.6 -1.5465122469,52.3774378227,609.6 -1.5473740435,52.3736309076,609.6 -1.5476581549,52.3697915629,609.6 -1.5473623069,52.3659525485,609.6 -1.5464891734,52.3621466133,609.6 -1.545046348,52.3584062155,609.6 -1.5430462749,52.3547632464,609.6 -1.5405061376,52.35124875900001,609.6 -1.5374477087,52.3478927039,609.6 -1.5338971602,52.34472367480001,609.6 -1.5298848382,52.3417686664,609.6 -1.5254450017,52.33905284470001,609.6 -1.5206155294,52.33659933460001,609.6 -1.5154375968,52.3344290237,609.6 -1.5099553259,52.332560386,609.6 -1.5042154102,52.3310093251,609.6 -1.4982667195,52.3297890406,609.6 -1.4921598862,52.3289099161,609.6 -1.4859468772,52.3283794315,609.6 -1.4796805556,52.3282021004,609.6 -1.4734142339,52.3283794315,609.6 -1.4672012249,52.3289099161,609.6 -1.4610943916,52.3297890406,609.6 -1.4551457009,52.3310093251,609.6 -1.4494057852,52.332560386,609.6 -1.4439235143,52.3344290237,609.6 -1.4387455817,52.33659933460001,609.6 -1.4339161094,52.33905284470001,609.6 -1.4294762729,52.3417686664,609.6 -1.4254639509,52.34472367480001,609.6 -1.4219134024,52.3478927039,609.6 -1.4188549735,52.35124875900001,609.6 -1.4163148362,52.3547632464,609.6 -1.4143147631,52.3584062155,609.6 -1.4128719377,52.3621466133,609.6 -1.4119988042,52.3659525485,609.6 -1.4117029562,52.3697915629,609.6 -1.4119870676,52.3736309076,609.6 -1.4128488642,52.3774378227,609.6 -1.4142811383,52.38117981629999,609.6 -1.4162718053,52.3848249429,609.6 -1.4188040018,52.38834207600001,609.6 -1.4218562257,52.3917011751,609.6 -1.4254025162,52.3948735425,609.6 -1.4294126724,52.3978320702,609.6 -1.4338525089,52.40055147210001,609.6 -1.4386841471,52.4030085014,609.6 -1.4438663375,52.40518215070001,609.6 -1.4493548135,52.4070538323,609.6 -1.4551026699,52.408607539,609.6 -1.4610607668,52.409829981,609.6 -1.4671781513,52.41071070140001,609.6 -1.4734024973,52.4112421657,609.6 -1.4796805556,52.41141982709999,609.6 + + + + +
+ + EGRU213B COVENTRY RWY 05 + 521952N 0013215W -
522016N 0013250W -
522042N 0013204W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to
522019N 0013128W -
521952N 0013215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5373944444,52.33113611109999,609.6 -1.52439425,52.3384789444,609.6 -1.5279657452,52.3405328775,609.6 -1.5312866019,52.3427390404,609.6 -1.5343395556,52.3450859722,609.6 -1.5473305556,52.3377472222,609.6 -1.5373944444,52.33113611109999,609.6 + + + + +
+ + EGRU213C COVENTRY RWY 23 + 522430N 0012519W -
522407N 0012443W -
522340N 0012530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to
522404N 0012606W -
522430N 0012519W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4218777778,52.4084555556,609.6 -1.4349076111,52.40112836110001,609.6 -1.4313348092,52.3990715077,609.6 -1.4280140169,52.39686238180001,609.6 -1.4249625,52.3945125,609.6 -1.4119222222,52.4018444444,609.6 -1.4218777778,52.4084555556,609.6 + + + + +
+ + EGRU214A EAST MIDLANDS + A circle, 2.5 NM radius, centred at 524952N 0011940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3277777778,52.8727165679,609.6 -1.3341222329,52.8725389176,609.6 -1.3404124051,52.8720074866,609.6 -1.3465944797,52.87112682170001,609.6 -1.3526155747,52.8699044571,609.6 -1.3584241967,52.8683508497,609.6 -1.3639706843,52.8664792888,609.6 -1.3692076354,52.8643057815,609.6 -1.3740903145,52.86184891479999,609.6 -1.3785770361,52.8591296956,609.6 -1.3826295214,52.8561713699,609.6 -1.3862132249,52.85299922270001,609.6 -1.3892976278,52.849640361,609.6 -1.391856497,52.846123481,609.6 -1.3938681056,52.8424786217,609.6 -1.3953154151,52.8387369078,609.6 -1.3961862161,52.8349302827,609.6 -1.396473228,52.8310912361,609.6 -1.3961741563,52.8272525253,609.6 -1.3952917062,52.8234468966,609.6 -1.393833555,52.8197068054,609.6 -1.3918122811,52.8160641401,609.6 -1.3892452525,52.8125499505,609.6 -1.3861544737,52.8091941841,609.6 -1.3825663951,52.80602543169999,609.6 -1.3785116842,52.8030706845,609.6 -1.3740249626,52.8003551059,609.6 -1.369144509,52.7979018179,609.6 -1.363911933,52.7957317053,609.6 -1.3583718213,52.7938632398,609.6 -1.3525713588,52.7923123228,609.6 -1.3465599289,52.7910921522,609.6 -1.3403886961,52.79021311,609.6 -1.3341101731,52.7896826753,609.6 -1.3277777778,52.78950536090001,609.6 -1.3214453824,52.7896826753,609.6 -1.3151668594,52.79021311,609.6 -1.3089956266,52.7910921522,609.6 -1.3029841968,52.7923123228,609.6 -1.2971837343,52.7938632398,609.6 -1.2916436225,52.7957317053,609.6 -1.2864110466,52.7979018179,609.6 -1.2815305929,52.8003551059,609.6 -1.2770438713,52.8030706845,609.6 -1.2729891605,52.80602543169999,609.6 -1.2694010819,52.8091941841,609.6 -1.2663103031,52.8125499505,609.6 -1.2637432744,52.8160641401,609.6 -1.2617220006,52.8197068054,609.6 -1.2602638494,52.8234468966,609.6 -1.2593813993,52.8272525253,609.6 -1.2590823275,52.8310912361,609.6 -1.2593693395,52.8349302827,609.6 -1.2602401405,52.8387369078,609.6 -1.2616874499,52.8424786217,609.6 -1.2636990586,52.846123481,609.6 -1.2662579278,52.849640361,609.6 -1.2693423307,52.85299922270001,609.6 -1.2729260341,52.8561713699,609.6 -1.2769785194,52.8591296956,609.6 -1.2814652411,52.86184891479999,609.6 -1.2863479202,52.8643057815,609.6 -1.2915848713,52.8664792888,609.6 -1.2971313589,52.8683508497,609.6 -1.3029399809,52.8699044571,609.6 -1.3089610759,52.87112682170001,609.6 -1.3151431504,52.8720074866,609.6 -1.3214333226,52.8725389176,609.6 -1.3277777778,52.8727165679,609.6 + + + + +
+ + EGRU214B EAST MIDLANDS RWY 09 + 524929N 0012515W -
525002N 0012517W -
525003N 0012347W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to
524931N 0012345W -
524929N 0012515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4208305556,52.824775,609.6 -1.3957835,52.8252495278,609.6 -1.3963064082,52.8282329641,609.6 -1.3964730465,52.8312314664,609.6 -1.3962824722,52.8342294444,609.6 -1.421275,52.8337555556,609.6 -1.4208305556,52.824775,609.6 + + + + +
+ + EGRU214C EAST MIDLANDS RWY 27 + 525014N 0011405W -
524941N 0011403W -
524940N 0011534W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to
525012N 0011535W -
525014N 0011405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2346666667,52.83716666670001,609.6 -1.2597063611,52.8367260278,609.6 -1.2592174925,52.8337397508,609.6 -1.2590853456,52.8307399007,609.6 -1.2593105556,52.82774208330001,609.6 -1.2342138889,52.8281833333,609.6 -1.2346666667,52.83716666670001,609.6 + + + + +
+ + EGRU215A NOTTINGHAM + A circle, 2 NM radius, centred at 525515N 0010448W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.08,52.95411721650001,609.6 -1.0856666656,52.95394067319999,609.6 -1.0912731259,52.9534129191,609.6 -1.0967598197,52.95253956100001,609.6 -1.1020684668,52.95132987720001,609.6 -1.1071426907,52.9497967178,609.6 -1.1119286206,52.9479563679,609.6 -1.1163754663,52.94582837309999,609.6 -1.1204360586,52.94343533090001,609.6 -1.1240673509,52.94080264940001,609.6 -1.1272308755,52.9379582765,609.6 -1.1298931505,52.9349324012,609.6 -1.1320260322,52.93175713309999,609.6 -1.1336070103,52.9284661594,609.6 -1.1346194424,52.92509438740001,609.6 -1.1350527254,52.9216775732,609.6 -1.1349024025,52.9182519421,609.6 -1.1341702043,52.9148538046,609.6 -1.1328640255,52.9115191711,609.6 -1.1309978346,52.90828337109999,609.6 -1.1285915213,52.9051806792,609.6 -1.1256706811,52.902243953,609.6 -1.1222663398,52.8995042861,609.6 -1.1184146226,52.89699068,609.6 -1.1141563688,52.8947297385,609.6 -1.1095366993,52.8927453873,609.6 -1.1046045384,52.8910586221,609.6 -1.0994120974,52.8896872876,609.6 -1.0940143241,52.8886458902,609.6 -1.0884683244,52.8879454451,609.6 -1.0828327612,52.88759336060001,609.6 -1.0771672388,52.88759336060001,609.6 -1.0715316756,52.8879454451,609.6 -1.0659856759,52.8886458902,609.6 -1.0605879026,52.8896872876,609.6 -1.0553954616,52.8910586221,609.6 -1.0504633007,52.8927453873,609.6 -1.0458436312,52.8947297385,609.6 -1.0415853774,52.89699068,609.6 -1.0377336602,52.8995042861,609.6 -1.0343293189,52.902243953,609.6 -1.0314084787,52.9051806792,609.6 -1.0290021654,52.90828337109999,609.6 -1.0271359745,52.9115191711,609.6 -1.0258297957,52.9148538046,609.6 -1.0250975975,52.9182519421,609.6 -1.0249472746,52.9216775732,609.6 -1.0253805576,52.92509438740001,609.6 -1.0263929897,52.9284661594,609.6 -1.0279739678,52.93175713309999,609.6 -1.0301068495,52.9349324012,609.6 -1.0327691245,52.9379582765,609.6 -1.0359326491,52.94080264940001,609.6 -1.0395639414,52.94343533090001,609.6 -1.0436245337,52.94582837309999,609.6 -1.0480713794,52.9479563679,609.6 -1.0528573093,52.9497967178,609.6 -1.0579315332,52.95132987720001,609.6 -1.0632401803,52.95253956100001,609.6 -1.0687268741,52.9534129191,609.6 -1.0743333344,52.95394067319999,609.6 -1.08,52.95411721650001,609.6 + + + + +
+ + EGRU215B NOTTINGHAM RWY 03 + 525228N 0010627W -
525244N 0010715W -
525333N 0010632W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525320N 0010542W -
525228N 0010627W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1075944444,52.8745638889,609.6 -1.09513225,52.8888314444,609.6 -1.0998531952,52.8897890795,609.6 -1.1044119397,52.89100072210001,609.6 -1.1087712222,52.8924564722,609.6 -1.120725,52.87876666670001,609.6 -1.1075944444,52.8745638889,609.6 + + + + +
+ + EGRU215C NOTTINGHAM RWY 21 + 525754N 0010243W -
525738N 0010156W -
525647N 0010241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525704N 0010327W -
525754N 0010243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0454,52.9648666667,609.6 -1.0573920833,52.9511852778,609.6 -1.0529431955,52.9498260518,609.6 -1.0487162267,52.94822936720001,609.6 -1.0447458056,52.9464083333,609.6 -1.0322444444,52.96066666670001,609.6 -1.0454,52.9648666667,609.6 + + + + +
+ + EGRU215D NOTTINGHAM RWY 09 + 525452N 0010933W -
525524N 0010935W -
525526N 0010805W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525454N 0010803W -
525452N 0010933W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1592722222,52.9143111111,609.6 -1.1341868056,52.9149089167,609.6 -1.1348516491,52.9178856696,609.6 -1.1350698583,52.9208865282,609.6 -1.1348395556,52.9238870556,609.6 -1.1598416667,52.9232916667,609.6 -1.1592722222,52.9143111111,609.6 + + + + +
+ + EGRU215E NOTTINGHAM RWY 27 + 525537N 0005958W -
525505N 0005956W -
525503N 0010131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525535N 0010133W -
525537N 0005958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9993333332999998,52.9270222222,609.6 -1.0257090556,52.9264241111,609.6 -1.0250980782,52.9234437562,609.6 -1.0249341478,52.9204422491,609.6 -1.0252185,52.91744402780001,609.6 -0.9987611111,52.9180444444,609.6 -0.9993333332999998,52.9270222222,609.6 + + + + +
+ + EGRU216A LEICESTER + A circle, 2 NM radius, centred at 523628N 0010155W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0319444444,52.6410634276,609.6 -1.0375705691,52.6408868765,609.6 -1.0431369207,52.6403590989,609.6 -1.0485843657,52.6394857017,609.6 -1.053855042,52.6382759635,609.6 -1.0588929776,52.6367427346,609.6 -1.0636446878,52.6349023004,609.6 -1.0680597463,52.6327742071,609.6 -1.0720913215,52.6303810526,609.6 -1.0756966742,52.627748246,609.6 -1.0788376114,52.6249037357,609.6 -1.0814808896,52.62187771209999,609.6 -1.0835985651,52.6187022857,609.6 -1.085168287,52.6154111452,609.6 -1.08617353,52.6120391994,609.6 -1.0866037648,52.60862220600001,609.6 -1.0864545645,52.6051963924,609.6 -1.0857276454,52.6017980707,609.6 -1.0844308436,52.59846325349999,609.6 -1.082578026,52.5952272725,609.6 -1.0801889387,52.5921244045,609.6 -1.0772889928,52.5891875093,609.6 -1.0739089916,52.5864476827,609.6 -1.0700848014,52.5839339285,609.6 -1.0658569699,52.5816728523,609.6 -1.0612702954,52.5796883817,609.6 -1.0563733535,52.5780015143,609.6 -1.0512179835,52.5766300961,609.6 -1.0458587418,52.5755886349,609.6 -1.0403523279,52.57488814669999,609.6 -1.0347569877,52.57453604049999,609.6 -1.0291319012,52.57453604049999,609.6 -1.023536561,52.57488814669999,609.6 -1.0180301471,52.5755886349,609.6 -1.0126709054,52.5766300961,609.6 -1.0075155354,52.5780015143,609.6 -1.0026185935,52.5796883817,609.6 -0.998031919,52.5816728523,609.6 -0.9938040874,52.5839339285,609.6 -0.9899798973,52.5864476827,609.6 -0.9865998961,52.5891875093,609.6 -0.9836999502,52.5921244045,609.6 -0.9813108629,52.5952272725,609.6 -0.9794580453000001,52.59846325349999,609.6 -0.9781612435,52.6017980707,609.6 -0.9774343243999999,52.6051963924,609.6 -0.9772851241,52.60862220600001,609.6 -0.9777153589000001,52.6120391994,609.6 -0.9787206019,52.6154111452,609.6 -0.9802903238000001,52.6187022857,609.6 -0.9824079993,52.62187771209999,609.6 -0.9850512774,52.6249037357,609.6 -0.9881922147000001,52.627748246,609.6 -0.9917975674,52.6303810526,609.6 -0.9958291424999999,52.6327742071,609.6 -1.000244201,52.6349023004,609.6 -1.0049959113,52.6367427346,609.6 -1.0100338469,52.6382759635,609.6 -1.0153045232,52.6394857017,609.6 -1.0207519682,52.6403590989,609.6 -1.0263183198,52.6408868765,609.6 -1.0319444444,52.6410634276,609.6 + + + + +
+ + EGRU216B LEICESTER RWY 04 + 523354N 0010406W -
523413N 0010448W -
523454N 0010358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523438N 0010312W -
523354N 0010406W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0683138889,52.56495,609.6 -1.0533300833,52.5771455833,609.6 -1.0578004505,52.57845176989999,609.6 -1.0620583556,52.5799992746,609.6 -1.0660687778,52.5817753889,609.6 -1.0801166667,52.5703388889,609.6 -1.0683138889,52.56495,609.6 + + + + +
+ + EGRU216C LEICESTER RWY 22 + 523845N 0005914W -
523826N 0005831W -
523744N 0005923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523806N 0010002W -
523845N 0005914W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9871722222,52.6458638889,609.6 -1.0005339722,52.63502688890001,609.6 -0.9966043646999999,52.6331813756,609.6 -0.9929662177,52.6311266371,609.6 -0.9896495,52.6288796111,609.6 -0.9753499999999999,52.640475,609.6 -0.9871722222,52.6458638889,609.6 + + + + +
+ + EGRU216D LEICESTER RWY 06 + 523417N 0010449W -
523441N 0010525W -
523513N 0010428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523450N 0010349W -
523417N 0010449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0803583333,52.5713138889,609.6 -1.0636405833,52.5806598333,609.6 -1.0675359805,52.58251512939999,609.6 -1.0711404251,52.5845772236,609.6 -1.0744244167,52.58682925000001,609.6 -1.090325,52.57793888890001,609.6 -1.0803583333,52.5713138889,609.6 + + + + +
+ + EGRU216E LEICESTER RWY 24 + 523827N 0005840W -
523803N 0005804W -
523729N 0005905W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523754N 0005938W -
523827N 0005840W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9776805556,52.6407972222,609.6 -0.9939642500000001,52.6317283056,609.6 -0.9905625572,52.6295401098,609.6 -0.9875002127999999,52.6271736895,609.6 -0.9848022778,52.6246484444,609.6 -0.9677,52.6341722222,609.6 -0.9776805556,52.6407972222,609.6 + + + + +
+ + EGRU216F LEICESTER RWY 10 + 523631N 0010647W -
523703N 0010641W -
523657N 0010506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523625N 0010512W -
523631N 0010647W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1130722222,52.6085833333,609.6 -1.0866007222,52.6068874444,609.6 -1.0865119041,52.6098905627,609.6 -1.0859786876,52.61287657690001,609.6 -1.0850053333,52.6158211667,609.6 -1.1115138889,52.6175194444,609.6 -1.1130722222,52.6085833333,609.6 + + + + +
+ + EGRU216G LEICESTER RWY 28 + 523626N 0005704W -
523554N 0005709W -
523600N 0005844W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523632N 0005838W -
523626N 0005704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.950975,52.6071416667,609.6 -0.9772961944,52.6088584167,609.6 -0.9773605349,52.6058550628,609.6 -0.9778692787,52.6028674649,609.6 -0.9788181944,52.5999199444,609.6 -0.9525333333000001,52.59820555560001,609.6 -0.950975,52.6071416667,609.6 + + + + +
+ + EGRU216H LEICESTER RWY 15 + 523841N 0010436W -
523857N 0010350W -
523818N 0010314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523801N 0010359W -
523841N 0010436W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.076675,52.644675,609.6 -1.0663972778,52.6336289722,609.6 -1.0624252862,52.6354151885,609.6 -1.0582044025,52.6369760432,609.6 -1.0537690556,52.6382987778,609.6 -1.0638138889,52.6490972222,609.6 -1.076675,52.644675,609.6 + + + + +
+ + EGRU216I LEICESTER RWY 33 + 523401N 0005915W -
523345N 0010001W -
523435N 0010048W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523450N 0010001W -
523401N 0005915W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9875722222,52.56698055559999,609.6 -1.0002493889,52.5806593611,609.6 -1.0043947656,52.5790293299,609.6 -1.0087643261,52.5776335702,609.6 -1.0133225,52.5764834444,609.6 -1.0004111111,52.56255555560001,609.6 -0.9875722222,52.56698055559999,609.6 + + + + +
+ + EGRU216J LEICESTER RWY 16 + 523837N 0010440W -
523854N 0010355W -
523817N 0010318W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523759N 0010403W -
523837N 0010440W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0777805556,52.6435361111,609.6 -1.0673638056,52.6331404444,609.6 -1.0634615593,52.63498123910001,609.6 -1.059302093,52.63660032759999,609.6 -1.0549193333,52.6379845,609.6 -1.0651611111,52.6482083333,609.6 -1.0777805556,52.6435361111,609.6 + + + + +
+ + EGRU216K LEICESTER RWY 34 + 523405N 0005906W -
523348N 0005952W -
523437N 0010040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523453N 0005954W -
523405N 0005906W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9850805556000001,52.5681166667,609.6 -0.9984237778,52.5814858611,609.6 -1.0024525214,52.5797529201,609.6 -1.00672106,52.5782481656,609.6 -1.0111946667,52.5769838333,609.6 -0.9976777778,52.5634444444,609.6 -0.9850805556000001,52.5681166667,609.6 + + + + +
+ + EGRU217A NORTHAMPTON/SYWELL + A circle, 2 NM radius, centred at 521822N 0004732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7922222222,52.3393984685,609.6 -0.7978099840999999,52.3392219097,609.6 -0.8033383821,52.3386941093,609.6 -0.8087486871,52.3378206743,609.6 -0.8139834327,52.3366108832,609.6 -0.8189870296,52.33507758699999,609.6 -0.8237063585999999,52.3332370711,609.6 -0.8280913375999999,52.3311088823,609.6 -0.8320954543,52.3287156191,609.6 -0.8356762609,52.3260826912,609.6 -0.8387958239,52.32323804800001,609.6 -0.8414211255,52.3202118809,609.6 -0.8435244113000001,52.3170363014,609.6 -0.8450834812,52.3137449995,609.6 -0.8460819208,52.3103728857,609.6 -0.8465092708,52.3069557192,609.6 -0.8463611324,52.303529729,609.6 -0.8456392082999999,52.3001312293,609.6 -0.8443512793,52.2967962348,609.6 -0.8425111163,52.293560079,609.6 -0.8401383293,52.290457041,609.6 -0.8372581551,52.2875199827,609.6 -0.8339011864,52.284780002,609.6 -0.8301030446,52.2822661048,609.6 -0.8259040010000001,52.2800048986,609.6 -0.8213485493,52.278020313,609.6 -0.8164849347000001,52.27633334690001,609.6 -0.8113646445,52.2749618482,609.6 -0.806041865,52.2739203253,609.6 -0.8005729110000001,52.2732197955,609.6 -0.7950156334,52.27286766840001,609.6 -0.7894288111,52.27286766840001,609.6 -0.7838715335000001,52.2732197955,609.6 -0.7784025793999999,52.2739203253,609.6 -0.7730797999,52.2749618482,609.6 -0.7679595097,52.27633334690001,609.6 -0.7630958952,52.278020313,609.6 -0.7585404435000001,52.2800048986,609.6 -0.7543413999000002,52.2822661048,609.6 -0.7505432581,52.284780002,609.6 -0.7471862893000001,52.2875199827,609.6 -0.7443061150999999,52.290457041,609.6 -0.7419333280999999,52.293560079,609.6 -0.7400931651,52.2967962348,609.6 -0.7388052361999999,52.3001312293,609.6 -0.7380833120999999,52.303529729,609.6 -0.7379351735999999,52.3069557192,609.6 -0.7383625236,52.3103728857,609.6 -0.7393609633,52.3137449995,609.6 -0.7409200331,52.3170363014,609.6 -0.7430233189,52.3202118809,609.6 -0.7456486206,52.32323804800001,609.6 -0.7487681836,52.3260826912,609.6 -0.7523489901,52.3287156191,609.6 -0.7563531068,52.3311088823,609.6 -0.7607380858,52.3332370711,609.6 -0.7654574149,52.33507758699999,609.6 -0.7704610117999999,52.3366108832,609.6 -0.7756957574,52.3378206743,609.6 -0.7811060622999999,52.3386941093,609.6 -0.7866344602999999,52.3392219097,609.6 -0.7922222222,52.3393984685,609.6 + + + + +
+ + EGRU217B NORTHAMPTON/SYWELL RWY 03L + 521535N 0004908W -
521549N 0004956W -
521641N 0004917W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521627N 0004829W -
521535N 0004908W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8188444444000001,52.25975,609.6 -0.8080391111,52.2742679167,609.6 -0.812654855,52.2752715462,609.6 -0.8171045318000001,52.27652619300001,609.6 -0.8213519722,52.2780216389,609.6 -0.8321666666999999,52.2634861111,609.6 -0.8188444444000001,52.25975,609.6 + + + + +
+ + EGRU217C NORTHAMPTON/SYWELL RWY 21R + 522108N 0004558W -
522054N 0004510W -
522003N 0004548W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
522017N 0004636W -
522108N 0004558W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7660416667000001,52.3521972222,609.6 -0.7766436667,52.3380003611,609.6 -0.7720147602,52.3370096914,609.6 -0.7675507069,52.3357673179,609.6 -0.7632879166999998,52.3342833611,609.6 -0.7526944444,52.3484638889,609.6 -0.7660416667000001,52.3521972222,609.6 + + + + +
+ + EGRU217D NORTHAMPTON/SYWELL RWY 03R + 521535N 0004902W -
521548N 0004950W -
521639N 0004912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521626N 0004824W -
521535N 0004902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.817225,52.2596388889,609.6 -0.8065377222,52.2740019167,609.6 -0.8112001893,52.2749240222,609.6 -0.8157083104,52.2761001429,609.6 -0.8200254167000001,52.27752069440001,609.6 -0.8305472222,52.263375,609.6 -0.817225,52.2596388889,609.6 + + + + +
+ + EGRU217E NORTHAMPTON/SYWELL RWY 21L + 522102N 0004556W -
522049N 0004508W -
522002N 0004543W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
522016N 0004631W -
522102N 0004556W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7655472222,52.35060277780001,609.6 -0.77516825,52.3377156111,609.6 -0.7705856744,52.3366441745,609.6 -0.7661797483,52.33532380890001,609.6 -0.7619864167,52.3337653056,609.6 -0.7522000000000001,52.3468694444,609.6 -0.7655472222,52.35060277780001,609.6 + + + + +
+ + EGRU217F NORTHAMPTON/SYWELL RWY 05 + 521618N 0005049W -
521643N 0005121W -
521715N 0005014W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521651N 0004939W -
521618N 0005049W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8469,52.2715333333,609.6 -0.8275625,52.2808424722,609.6 -0.8311402354,52.28290235400001,609.6 -0.834400312,52.2851519226,609.6 -0.8373160833,52.2875728056,609.6 -0.8559361111,52.2786083333,609.6 -0.8469,52.2715333333,609.6 + + + + +
+ + EGRU217G NORTHAMPTON/SYWELL RWY 23 + 522015N 0004401W -
521949N 0004328W -
521916N 0004437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521943N 0004507W -
522015N 0004401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7335999999999999,52.33738611110001,609.6 -0.7520706944000001,52.32852977780001,609.6 -0.7489313660999999,52.3262153965,609.6 -0.7461463394999999,52.3237366888,609.6 -0.7437383333000002,52.3211139444,609.6 -0.72455,52.3303138889,609.6 -0.7335999999999999,52.33738611110001,609.6 + + + + +
+ + EGRU217H NORTHAMPTON/SYWELL RWY 14 + 522016N 0005109W -
522039N 0005032W -
522000N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521938N 0005004W -
522016N 0005109W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8524527778,52.3377472222,609.6 -0.8343298333,52.3271384167,609.6 -0.8310595854,52.32938324580001,609.6 -0.8274715191999998,52.3314378811,609.6 -0.8235949444,52.3332855,609.6 -0.8423083333000001,52.3442416667,609.6 -0.8524527778,52.3377472222,609.6 + + + + +
+ + EGRU217I NORTHAMPTON/SYWELL RWY 32 + 521638N 0004340W -
521614N 0004417W -
521653N 0004522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521717N 0004448W -
521638N 0004340W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7279055556,52.2771305556,609.6 -0.7465651944000001,52.2880981667,609.6 -0.7494051075999999,52.2856446324,609.6 -0.7525943514,52.2833582938,609.6 -0.7561068611,52.28125780559999,609.6 -0.7380333333,52.2706361111,609.6 -0.7279055556,52.2771305556,609.6 + + + + +
+ + EGRU218A CRANFIELD + A circle, 2 NM radius, centred at 520420N 0003700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6166666667,52.1055109067,609.6 -0.6222251498,52.105334342,609.6 -0.6277245811,52.1048065238,609.6 -0.6331065404,52.10393305929999,609.6 -0.6383138633,52.1027232271,609.6 -0.6432912525,52.1011898783,609.6 -0.6479858678,52.0993492989,609.6 -0.6523478896,52.0972210357,609.6 -0.6563310496,52.0948276879,609.6 -0.6598931220000001,52.0921946656,609.6 -0.6629963717,52.08934991900001,609.6 -0.6656079531,52.0863236401,609.6 -0.6677002562,52.0831479414,609.6 -0.6692511960999999,52.0798565142,609.6 -0.670244443,52.0764842696,609.6 -0.6706695909,52.0730669685,609.6 -0.6705222627,52.0696408411,609.6 -0.6698041505,52.06624220319999,609.6 -0.6685229932,52.0629070708,609.6 -0.6666924882,52.0596707793,609.6 -0.6643321417,52.0565676093,609.6 -0.6614670575,52.0536304244,609.6 -0.6581276673999999,52.05089032410001,609.6 -0.6543494062,52.0483763159,609.6 -0.6501723341,52.0461150089,609.6 -0.6456407123,52.04413033400001,609.6 -0.6408025339,52.0424432914,609.6 -0.6357090174,52.04107173000001,609.6 -0.6304140667,52.0400301594,609.6 -0.6249737029,52.03932959739999,609.6 -0.6194454757,52.03897745410001,609.6 -0.6138878577,52.03897745410001,609.6 -0.6083596304,52.03932959739999,609.6 -0.6029192665999999,52.0400301594,609.6 -0.5976243159,52.04107173000001,609.6 -0.5925307995,52.0424432914,609.6 -0.5876926211,52.04413033400001,609.6 -0.5831609992,52.0461150089,609.6 -0.5789839272,52.0483763159,609.6 -0.5752056659,52.05089032410001,609.6 -0.5718662758,52.0536304244,609.6 -0.5690011916,52.0565676093,609.6 -0.5666408451,52.0596707793,609.6 -0.5648103401,52.0629070708,609.6 -0.5635291828,52.06624220319999,609.6 -0.5628110707,52.0696408411,609.6 -0.5626637424000001,52.0730669685,609.6 -0.5630888903,52.0764842696,609.6 -0.5640821372,52.0798565142,609.6 -0.5656330771,52.0831479414,609.6 -0.5677253802,52.0863236401,609.6 -0.5703369616,52.08934991900001,609.6 -0.5734402114,52.0921946656,609.6 -0.5770022838,52.0948276879,609.6 -0.5809854437,52.0972210357,609.6 -0.5853474655999999,52.0993492989,609.6 -0.5900420809,52.1011898783,609.6 -0.59501947,52.1027232271,609.6 -0.6002267929,52.10393305929999,609.6 -0.6056087522,52.1048065238,609.6 -0.6111081835,52.105334342,609.6 -0.6166666667,52.1055109067,609.6 + + + + +
+ + EGRU218B CRANFIELD RWY 03 + 520134N 0003915W -
520151N 0004000W -
520247N 0003903W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to
520230N 0003819W -
520134N 0003915W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6541416667,52.0262083333,609.6 -0.6385356666999999,52.0417852222,609.6 -0.6428961638,52.0431237873,609.6 -0.6470435365,52.0446991176,609.6 -0.6509440556,52.0464984167,609.6 -0.6665305556,52.0309361111,609.6 -0.6541416667,52.0262083333,609.6 + + + + +
+ + EGRU218C CRANFIELD RWY 21 + 520710N 0003439W -
520653N 0003355W -
520552N 0003456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to
520609N 0003541W -
520710N 0003439W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5776055556,52.11955,609.6 -0.5946302778,52.1026172778,609.6 -0.5902709864,52.1012692712,609.6 -0.5861270565,52.09968460289999,609.6 -0.5822322778,52.09787619440001,609.6 -0.5651888889,52.1148222222,609.6 -0.5776055556,52.11955,609.6 + + + + +
+ + EGRU219A BARKSTON HEATH + A circle, 2 NM radius, centred at 525747N 0003337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5603222222000001,52.99626697899999,609.6 -0.565994404,52.9960904368,609.6 -0.5716063218,52.9955626858,609.6 -0.577098356,52.994689333,609.6 -0.5824121696,52.99347965639999,609.6 -0.5874913311,52.9919465064,609.6 -0.5922819171,52.9901061679,609.6 -0.5967330879,52.9879781863,609.6 -0.6007976284,52.9855851591,609.6 -0.6044324502,52.9829524945,609.6 -0.6075990482,52.9801081399,609.6 -0.6102639079,52.9770822846,609.6 -0.6123988586,52.9739070377,609.6 -0.6139813683000001,52.9706160864,609.6 -0.6149947786,52.9672443378,609.6 -0.6154284763,52.9638275476,609.6 -0.6152780005,52.96040194119999,609.6 -0.6145450841,52.9570038284,609.6 -0.6132376293,52.9536692196,609.6 -0.6113696187,52.950433444,609.6 -0.6089609616,52.9473307757,609.6 -0.6060372784,52.9443940723,609.6 -0.6026296253,52.94165442679999,609.6 -0.5987741625,52.93914084069999,609.6 -0.5945117693999999,52.9368799173,609.6 -0.5898876105,52.9348955822,609.6 -0.5849506575,52.9332088307,609.6 -0.5797531725,52.9318375075,609.6 -0.5743501564,52.93079611870001,609.6 -0.5687987704,52.9300956793,609.6 -0.5631577344000001,52.9297435978,609.6 -0.5574867100999999,52.9297435978,609.6 -0.551845674,52.9300956793,609.6 -0.546294288,52.93079611870001,609.6 -0.540891272,52.9318375075,609.6 -0.5356937869,52.9332088307,609.6 -0.530756834,52.9348955822,609.6 -0.526132675,52.9368799173,609.6 -0.5218702819,52.93914084069999,609.6 -0.5180148192,52.94165442679999,609.6 -0.5146071661,52.9443940723,609.6 -0.5116834828,52.9473307757,609.6 -0.5092748257,52.950433444,609.6 -0.5074068151,52.9536692196,609.6 -0.5060993604,52.9570038284,609.6 -0.5053664439,52.96040194119999,609.6 -0.5052159682,52.9638275476,609.6 -0.5056496659,52.9672443378,609.6 -0.5066630762,52.9706160864,609.6 -0.5082455858,52.9739070377,609.6 -0.5103805365,52.9770822846,609.6 -0.5130453963,52.9801081399,609.6 -0.5162119943,52.9829524945,609.6 -0.519846816,52.9855851591,609.6 -0.5239113565,52.9879781863,609.6 -0.5283625273,52.9901061679,609.6 -0.5331531134,52.9919465064,609.6 -0.5382322748,52.99347965639999,609.6 -0.5435460884,52.994689333,609.6 -0.5490381227,52.9955626858,609.6 -0.5546500404,52.9960904368,609.6 -0.5603222222000001,52.99626697899999,609.6 + + + + +
+ + EGRU219B BARKSTON HEATH RWY 06 + 525553N 0003743W -
525620N 0003812W -
525656N 0003637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525629N 0003608W -
525553N 0003743W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6285518889,52.931293,609.6 -0.6023251944,52.9414361667,609.6 -0.6053708766,52.9438101274,609.6 -0.6080502032,52.9463402205,609.6 -0.6103413333,52.94900586110001,609.6 -0.6365603611,52.9388649167,609.6 -0.6285518889,52.931293,609.6 + + + + +
+ + EGRU219C BARKSTON HEATH RWY 24 + 525943N 0002924W -
525916N 0002856W -
525837N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525904N 0003106W -
525943N 0002924W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4901250278,52.99536802779999,609.6 -0.51829125,52.9845253889,609.6 -0.5152459863,52.9821499092,609.6 -0.5125682452,52.979618365,609.6 -0.5102798056,52.9769513889,609.6 -0.4821061111,52.9877961667,609.6 -0.4901250278,52.99536802779999,609.6 + + + + +
+ + EGRU219D BARKSTON HEATH RWY 10 + 525756N 0003847W -
525827N 0003836W -
525813N 0003651W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525741N 0003655W -
525756N 0003847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6465194444,52.96551111109999,609.6 -0.6153789167,52.9613583333,609.6 -0.6153974861,52.964387462,609.6 -0.6149598521,52.96740506339999,609.6 -0.6140695278,52.9703861389,609.6 -0.6432944444000001,52.9742833333,609.6 -0.6465194444,52.96551111109999,609.6 + + + + +
+ + EGRU219E BARKSTON HEATH RWY 28 + 525709N 0002854W -
525638N 0002906W -
525651N 0003042W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525721N 0003023W -
525709N 0002854W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4816833333,52.9526333333,609.6 -0.5064422778,52.9559658056,609.6 -0.5077235244,52.9530372713,609.6 -0.509440117,52.95019118940001,609.6 -0.5115777500000001,52.9474511111,609.6 -0.4849027778,52.94386111110001,609.6 -0.4816833333,52.9526333333,609.6 + + + + +
+ + EGRU219F BARKSTON HEATH RWY 18 + 530037N 0003400W -
530038N 0003306W -
525945N 0003303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525946N 0003356W -
530037N 0003400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5665701111,53.01019069439999,609.6 -0.5656517222,52.9961111667,609.6 -0.5606649345,52.9962663366,609.6 -0.5556753315,52.9961485956,609.6 -0.5507238889,52.99575891670001,609.6 -0.5516831111,53.0105427222,609.6 -0.5665701111,53.01019069439999,609.6 + + + + +
+ + EGRU219G BARKSTON HEATH RWY 36 + 525449N 0003243W -
525448N 0003337W -
525547N 0003341W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525551N 0003247W -
525449N 0003243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.54540575,52.9136083333,609.6 -0.5465145,52.9307613889,609.6 -0.5513929375,52.9301394272,609.6 -0.5563443631,52.9297863492,609.6 -0.5613283056,52.9297050556,609.6 -0.5602594722000001,52.91325630560001,609.6 -0.54540575,52.9136083333,609.6 + + + + +
+ + EGRU220A WITTERING + A circle, 2.5 NM radius, centred at 523647N 0002833W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4759055555999999,52.6546625512,609.6 -0.4822183994000001,52.65448489570001,609.6 -0.4884772319,52.6539534489,609.6 -0.4946285077,52.6530727579,609.6 -0.5006196095,52.6518503568,609.6 -0.5063993013,52.6502967026,609.6 -0.5119181697,52.6484250848,609.6 -0.5171290495999999,52.64625151049999,609.6 -0.5219874283,52.6437945672,609.6 -0.5264518282,52.6410752618,609.6 -0.5304841608999999,52.6381168408,609.6 -0.5340500523,52.6349445897,609.6 -0.5371191351,52.631585616,609.6 -0.5396653057,52.6280686166,609.6 -0.5416669443,52.62442363110001,609.6 -0.5431070957,52.6206817852,609.6 -0.5439736099,52.6168750233,609.6 -0.5442592411,52.6130358359,609.6 -0.5439617044,52.6091969817,609.6 -0.54308369,52.6053912083,609.6 -0.5416328355,52.6016509723,609.6 -0.5396216554,52.5980081635,609.6 -0.5370674297,52.5944938332,609.6 -0.5339920525,52.5911379304,609.6 -0.5304218419,52.5879690473,609.6 -0.5263873122,52.58501417670001,609.6 -0.5219229123,52.5822984832,609.6 -0.5170667305,52.5798450902,609.6 -0.5118601699000001,52.5776748839,609.6 -0.5063475957,52.575806337,609.6 -0.5005759591,52.574255352,609.6 -0.4945943989,52.5730351276,609.6 -0.4884538261,52.5721560465,609.6 -0.4822064938,52.5716255882,609.6 -0.4759055555999999,52.5714482659,609.6 -0.4696046173,52.5716255882,609.6 -0.463357285,52.5721560465,609.6 -0.4572167122,52.5730351276,609.6 -0.4512351519999999,52.574255352,609.6 -0.4454635154000001,52.575806337,609.6 -0.4399509412,52.5776748839,609.6 -0.4347443806,52.5798450902,609.6 -0.4298881989,52.5822984832,609.6 -0.4254237989,52.58501417670001,609.6 -0.4213892692,52.5879690473,609.6 -0.4178190586,52.5911379304,609.6 -0.4147436814,52.5944938332,609.6 -0.4121894557,52.5980081635,609.6 -0.4101782756,52.6016509723,609.6 -0.4087274210999999,52.6053912083,609.6 -0.4078494068,52.6091969817,609.6 -0.40755187,52.6130358359,609.6 -0.4078375012,52.6168750233,609.6 -0.4087040154,52.6206817852,609.6 -0.4101441668,52.62442363110001,609.6 -0.4121458054,52.6280686166,609.6 -0.414691976,52.631585616,609.6 -0.4177610588,52.6349445897,609.6 -0.4213269502,52.6381168408,609.6 -0.4253592829,52.6410752618,609.6 -0.4298236828,52.6437945672,609.6 -0.4346820616,52.64625151049999,609.6 -0.4398929414,52.6484250848,609.6 -0.4454118097999999,52.6502967026,609.6 -0.4511915016,52.6518503568,609.6 -0.4571826034,52.6530727579,609.6 -0.4633338792000001,52.6539534489,609.6 -0.4695927117,52.65448489570001,609.6 -0.4759055555999999,52.6546625512,609.6 + + + + +
+ + EGRU220B WITTERING RWY 07 + 523532N 0003349W -
523603N 0003404W -
523619N 0003235W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to
523548N 0003220W -
523532N 0003349W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5636166667,52.5921861111,609.6 -0.5387953333,52.5967718611,609.6 -0.5405613037,52.5995733524,609.6 -0.5419912752,52.60244504039999,609.6 -0.54307775,52.605372,609.6 -0.5678833333,52.60078888889999,609.6 -0.5636166667,52.5921861111,609.6 + + + + +
+ + EGRU220C WITTERING RWY 25 + 523802N 0002317W -
523731N 0002302W -
523715N 0002431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to
523746N 0002447W -
523802N 0002317W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3881305556,52.6338611111,609.6 -0.4129719444,52.6293098333,609.6 -0.4112122551,52.6265062386,609.6 -0.4097894559999999,52.6236327327,609.6 -0.4087108889000001,52.6207042778,609.6 -0.3838527778,52.6252583333,609.6 -0.3881305556,52.6338611111,609.6 + + + + +
+ + EGRU222A OLD WARDEN + A circle, 2 NM radius, centred at 520512N 0001907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3186111111,52.1199552691,609.6 -0.3241713908,52.1197787048,609.6 -0.3296725996,52.1192508877,609.6 -0.3350562982,52.11837742500001,609.6 -0.3402653038,52.1171675954,609.6 -0.3452443011,52.1156342498,609.6 -0.3499404329,52.1137936743,609.6 -0.3543038634,52.1116654157,609.6 -0.3582883093,52.1092720731,609.6 -0.3618515313,52.1066390567,609.6 -0.364955782,52.10379431650001,609.6 -0.3675682054,52.1007680445,609.6 -0.3696611824,52.0975923532,609.6 -0.3712126211,52.0943009337,609.6 -0.3722061867000001,52.0909286972,609.6 -0.3726314698,52.08751140439999,609.6 -0.3724840918,52.0840852855,609.6 -0.3717657458,52.0806866562,609.6 -0.3704841729,52.0773515323,609.6 -0.3686530753,52.07411524919999,609.6 -0.3662919654,52.07101208730001,609.6 -0.3634259553,52.0680749102,609.6 -0.3600854865,52.06533481739999,609.6 -0.3563060054,52.062820816,609.6 -0.3521275850999999,52.0605595152,609.6 -0.347594501,52.05857484580001,609.6 -0.3427547618,52.056887808,609.6 -0.3376596025,52.05551625049999,609.6 -0.3323629441,52.0544746828,609.6 -0.326920826,52.05377412280001,609.6 -0.3213908161,52.0534219804,609.6 -0.3158314061,52.0534219804,609.6 -0.3103013962,52.05377412280001,609.6 -0.3048592781,52.0544746828,609.6 -0.2995626198,52.05551625049999,609.6 -0.2944674604,52.056887808,609.6 -0.2896277212,52.05857484580001,609.6 -0.2850946371,52.0605595152,609.6 -0.2809162168,52.062820816,609.6 -0.2771367357,52.06533481739999,609.6 -0.273796267,52.0680749102,609.6 -0.2709302568,52.07101208730001,609.6 -0.2685691469,52.07411524919999,609.6 -0.2667380493,52.0773515323,609.6 -0.2654564765,52.0806866562,609.6 -0.2647381305,52.0840852855,609.6 -0.2645907525,52.08751140439999,609.6 -0.2650160355,52.0909286972,609.6 -0.2660096011,52.0943009337,609.6 -0.2675610398,52.0975923532,609.6 -0.2696540168,52.1007680445,609.6 -0.2722664402,52.10379431650001,609.6 -0.2753706909,52.1066390567,609.6 -0.2789339129,52.1092720731,609.6 -0.2829183588,52.1116654157,609.6 -0.2872817893,52.1137936743,609.6 -0.2919779211,52.1156342498,609.6 -0.2969569184,52.1171675954,609.6 -0.302165924,52.11837742500001,609.6 -0.3075496226,52.1192508877,609.6 -0.3130508314,52.1197787048,609.6 -0.3186111111,52.1199552691,609.6 + + + + +
+ + EGRU222B OLD WARDEN RWY 03 + 520232N 0002041W -
520245N 0002128W -
520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520318N 0002006W -
520232N 0002041W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3446666667,52.0421166667,609.6 -0.3348690556,52.0549213889,609.6 -0.3394451207,52.0559533739,609.6 -0.3438518961,52.057235281,609.6 -0.3480535556,52.0587566944,609.6 -0.3578472222,52.0459527778,609.6 -0.3446666667,52.0421166667,609.6 + + + + +
+ + EGRU222C OLD WARDEN RWY 21 + 520753N 0001732W -
520739N 0001645W -
520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520706N 0001808W -
520753N 0001732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2923277778,52.1314555556,609.6 -0.3023411667,52.1184116944,609.6 -0.2977597768,52.11737904,609.6 -0.2933484744,52.11609621729999,609.6 -0.2891432222,52.1145736944,609.6 -0.279125,52.1276194444,609.6 -0.2923277778,52.1314555556,609.6 + + + + +
+ + EGRU222D OLD WARDEN RWY 03X + 520218N 0002051W -
520231N 0002139W -
520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520318N 0002005W -
520218N 0002051W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3476277778,52.03821666670001,609.6 -0.3348561389,52.0549188611,609.6 -0.339432504,52.05595012949999,609.6 -0.3438396998,52.05723131520001,609.6 -0.3480418889,52.0587520278,609.6 -0.3608055556,52.0420527778,609.6 -0.3476277778,52.03821666670001,609.6 + + + + +
+ + EGRU222E OLD WARDEN RWY 21X + 520753N 0001732W -
520739N 0001645W -
520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520706N 0001808W -
520753N 0001732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2923444444,52.13146111109999,609.6 -0.3023537222,52.1184141389,609.6 -0.2977706736,52.1173818267,609.6 -0.2933577082,52.1160992039,609.6 -0.2891508333,52.1145767222,609.6 -0.2791361111,52.127625,609.6 -0.2923444444,52.13146111109999,609.6 + + + + +
+ + EGRU223A PETERBOROUGH/CONINGTON + A circle, 2 NM radius, centred at 522805N 0001503W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2509305556,52.5013558845,609.6 -0.2565388288,52.5011793299,609.6 -0.2620875194,52.50065154170001,609.6 -0.2675176819,52.499778127,609.6 -0.2727716385,52.49856836429999,609.6 -0.2777935952,52.4970351043,609.6 -0.2825302375,52.4951946324,609.6 -0.286931299,52.49306649479999,609.6 -0.2909500969,52.4906732901,609.6 -0.2945440276,52.4880404274,609.6 -0.2976750187,52.48519585559999,609.6 -0.3003099319,52.48216976560001,609.6 -0.3024209115,52.4789942684,609.6 -0.3039856767,52.4757030532,609.6 -0.3049877539,52.4723310297,609.6 -0.3054166464,52.4689139562,609.6 -0.3052679403,52.4654880608,609.6 -0.3045433456,52.46208965680001,609.6 -0.3032506726,52.45875475750001,609.6 -0.3014037436,52.4555186956,609.6 -0.2990222414,52.45241574890001,609.6 -0.2961314959,52.4494787782,609.6 -0.2927622124,52.4467388803,609.6 -0.2889501434,52.44422505979999,609.6 -0.2847357077,52.4419639235,609.6 -0.2801635622,52.43997939970001,609.6 -0.2752821285,52.4382924865,609.6 -0.2701430821,52.4369210311,609.6 -0.2648008074,52.4358795413,609.6 -0.2593118247,52.43517903379999,609.6 -0.2537341961,52.43482691799999,609.6 -0.248126915,52.43482691799999,609.6 -0.2425492865,52.43517903379999,609.6 -0.2370603038,52.4358795413,609.6 -0.231718029,52.4369210311,609.6 -0.2265789826,52.4382924865,609.6 -0.221697549,52.43997939970001,609.6 -0.2171254034,52.4419639235,609.6 -0.2129109677,52.44422505979999,609.6 -0.2090988987,52.4467388803,609.6 -0.2057296152,52.4494787782,609.6 -0.2028388697,52.45241574890001,609.6 -0.2004573675,52.4555186956,609.6 -0.1986104385,52.45875475750001,609.6 -0.1973177656,52.46208965680001,609.6 -0.1965931708,52.4654880608,609.6 -0.1964444647,52.4689139562,609.6 -0.1968733572,52.4723310297,609.6 -0.1978754344,52.4757030532,609.6 -0.1994401997,52.4789942684,609.6 -0.2015511792,52.48216976560001,609.6 -0.2041860924,52.48519585559999,609.6 -0.2073170836,52.4880404274,609.6 -0.2109110142,52.4906732901,609.6 -0.2149298121,52.49306649479999,609.6 -0.2193308736,52.4951946324,609.6 -0.2240675159,52.4970351043,609.6 -0.2290894726,52.49856836429999,609.6 -0.2343434292,52.499778127,609.6 -0.2397735918,52.50065154170001,609.6 -0.2453222823,52.5011793299,609.6 -0.2509305556,52.5013558845,609.6 + + + + +
+ + EGRU223B PETERBOROUGH/CONINGTON RWY 10 + 522803N 0001956W -
522835N 0001952W -
522830N 0001815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to
522758N 0001819W -
522803N 0001956W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3321527778,52.4673944444,609.6 -0.3053404444,52.46613588890001,609.6 -0.3054061395,52.4691397138,609.6 -0.3050281085,52.4721349212,609.6 -0.3042093333,52.4750971111,609.6 -0.3310083333,52.4763555556,609.6 -0.3321527778,52.4673944444,609.6 + + + + +
+ + EGRU223C PETERBOROUGH/CONINGTON RWY 28 + 522808N 0001017W -
522735N 0001021W -
522740N 0001152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to
522812N 0001147W -
522808N 0001017W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1714472222,52.4687722222,609.6 -0.1965159444,52.4699780556,609.6 -0.1964576045,52.46697486480001,609.6 -0.1968427065,52.4639806853,609.6 -0.1976680278,52.4610198889,609.6 -0.1725861111,52.4598138889,609.6 -0.1714472222,52.4687722222,609.6 + + + + +
+ + EGRU224A FENLAND + A circle, 2 NM radius, centred at 524422N 0000148W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0298666667,52.7727293506,609.6 -0.0355097506,52.7725528028,609.6 -0.0410928807,52.7720250351,609.6 -0.0465567445,52.7711516544,609.6 -0.05184330499999999,52.769941939,609.6 -0.0568964209,52.76840873939999,609.6 -0.0616624461,52.7665683408,609.6 -0.0660908021,52.76444028889999,609.6 -0.07013451580000001,52.7620471818,609.6 -0.0737507198,52.7594144279,609.6 -0.076901106,52.7565699754,609.6 -0.0795523311,52.7535440143,609.6 -0.0816763678,52.7503686545,609.6 -0.0832507985,52.74707758429999,609.6 -0.084259049,52.7437057116,609.6 -0.084690559,52.7402887937,609.6 -0.0845408891,52.7368630569,609.6 -0.0838117617,52.7334648127,609.6 -0.08251103730000001,52.7301300729,609.6 -0.0806526253,52.726894168,609.6 -0.078256332,52.7237913741,609.6 -0.0753476454,52.7208545501,609.6 -0.07195746209999999,52.7181147907,609.6 -0.06812175669999999,52.7156010987,609.6 -0.0638811987,52.7133400792,609.6 -0.0592807215,52.7113556589,609.6 -0.05436904649999999,52.7096688344,609.6 -0.04919816859999999,52.70829745149999,609.6 -0.0438228081,52.7072560171,609.6 -0.0382998343,52.70655554699999,609.6 -0.0326876677,52.70620345,609.6 -0.0270456657,52.70620345,609.6 -0.021433499,52.70655554699999,609.6 -0.0159105253,52.7072560171,609.6 -0.0105351647,52.70829745149999,609.6 -0.0053642868,52.7096688344,609.6 -0.0004526119,52.7113556589,609.6 0.0041478653,52.7133400792,609.6 0.0083884233,52.7156010987,609.6 0.0122241288,52.7181147907,609.6 0.0156143121,52.7208545501,609.6 0.0185229986,52.7237913741,609.6 0.020919292,52.726894168,609.6 0.0227777039,52.7301300729,609.6 0.0240784284,52.7334648127,609.6 0.0248075558,52.7368630569,609.6 0.0249572257,52.7402887937,609.6 0.0245257156,52.7437057116,609.6 0.0235174651,52.74707758429999,609.6 0.0219430344,52.7503686545,609.6 0.0198189978,52.7535440143,609.6 0.0171677727,52.7565699754,609.6 0.0140173865,52.7594144279,609.6 0.0104011825,52.7620471818,609.6 0.0063574687,52.76444028889999,609.6 0.0019291128,52.7665683408,609.6 -0.0028369125,52.76840873939999,609.6 -0.007890028300000001,52.769941939,609.6 -0.0131765888,52.7711516544,609.6 -0.0186404526,52.7720250351,609.6 -0.0242235827,52.7725528028,609.6 -0.0298666667,52.7727293506,609.6 + + + + +
+ + EGRU224B FENLAND RWY 18 + 524711N 0000210W -
524710N 0000116W -
524620N 0000118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to
524621N 0000211W -
524711N 0000210W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.03605,52.7863611111,609.6 -0.0364105278,52.7724917222,609.6 -0.0314710385,52.7727151248,609.6 -0.0265184494,52.77266731539999,609.6 -0.0215931944,52.7723486944,609.6 -0.0212277778,52.7862166667,609.6 -0.03605,52.7863611111,609.6 + + + + +
+ + EGRU224C FENLAND RWY 36 + 524130N 0000125W -
524131N 0000219W -
524224N 0000217W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to
524223N 0000124W -
524130N 0000125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0237138889,52.6916888889,609.6 -0.0233277778,52.7063969722,609.6 -0.0282594659,52.7061736718,609.6 -0.0332042095,52.70622110830001,609.6 -0.0381218333,52.7065389167,609.6 -0.0385027778,52.6918305556,609.6 -0.0237138889,52.6916888889,609.6 + + + + +
+ + EGRU225A DUXFORD + A circle, 2 NM radius, centred at 520526N 0000753E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1315027778,52.123808025,609.6 0.1259420186,52.1236314608,609.6 0.1204403355,52.123103644,609.6 0.1150561727,52.12223018179999,609.6 0.109846718,52.1210203528,609.6 0.1048672915,52.11948700819999,609.6 0.1001707551,52.1176464337,609.6 0.0958069486,52.1155181763,609.6 0.0918221595,52.1131248351,609.6 0.08825863069999998,52.11049182030001,609.6 0.0851541128,52.1076470817,609.6 0.08254146480000001,52.10462081160001,609.6 0.0804483079,52.1014451223,609.6 0.0788967361,52.0981537048,609.6 0.0779030855,52.0947814705,609.6 0.0774777663,52.0913641799,609.6 0.07762515759999999,52.0879380633,609.6 0.078343566,52.0845394362,609.6 0.07962524980000001,52.08120431460001,609.6 0.0814565055,52.0779680338,609.6 0.0838178192,52.0748648741,609.6 0.0866840764,52.0719276991,609.6 0.09002483299999998,52.06918760819999,609.6 0.0938046397,52.0666736086,609.6 0.0979834198,52.0644123095,609.6 0.1025168941,52.0624276416,609.6 0.1073570499,52.06074060499999,609.6 0.1124526477,52.0593690485,609.6 0.1177497618,52.05832748169999,609.6 0.1231923481,52.0576269221,609.6 0.1287228336,52.0572747801,609.6 0.1342827219,52.0572747801,609.6 0.1398132075,52.0576269221,609.6 0.1452557938,52.05832748169999,609.6 0.1505529079,52.0593690485,609.6 0.1556485057,52.06074060499999,609.6 0.1604886614,52.0624276416,609.6 0.1650221357,52.0644123095,609.6 0.1692009158,52.0666736086,609.6 0.1729807226,52.06918760819999,609.6 0.1763214791,52.0719276991,609.6 0.1791877364,52.0748648741,609.6 0.18154905,52.0779680338,609.6 0.1833803058,52.08120431460001,609.6 0.1846619895,52.0845394362,609.6 0.1853803979,52.0879380633,609.6 0.1855277892,52.0913641799,609.6 0.1851024701,52.0947814705,609.6 0.1841088195,52.0981537048,609.6 0.1825572476,52.1014451223,609.6 0.1804640907,52.10462081160001,609.6 0.1778514427,52.1076470817,609.6 0.1747469248,52.11049182030001,609.6 0.1711833961,52.1131248351,609.6 0.167198607,52.1155181763,609.6 0.1628348005,52.1176464337,609.6 0.158138264,52.11948700819999,609.6 0.1531588375,52.1210203528,609.6 0.1479493829,52.12223018179999,609.6 0.1425652201,52.123103644,609.6 0.137063537,52.1236314608,609.6 0.1315027778,52.123808025,609.6 + + + + +
+ + EGRU225B DUXFORD RWY 06L + 520342N 0000358E -
520409N 0000331E -
520441N 0000453E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520413N 0000519E -
520342N 0000358E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0662027778,52.0616638889,609.6 0.0885908611,52.0702925556,609.6 0.0858030761,52.07276003560001,609.6 0.08338763709999999,52.07537239800001,609.6 0.08136430560000001,52.0781083611,609.6 0.0584833333,52.0692888889,609.6 0.0662027778,52.0616638889,609.6 + + + + +
+ + EGRU225C DUXFORD RWY 24R + 520716N 0001135E -
520648N 0001203E -
520619N 0001047E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520646N 0001018E -
520716N 0001135E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1931527778,52.1210833333,609.6 0.1716298056,52.1128239167,609.6 0.1747339861,52.1105024373,609.6 0.177484965,52.10801790679999,609.6 0.1798603056,52.1053906111,609.6 0.2008861111,52.1134583333,609.6 0.1931527778,52.1210833333,609.6 + + + + +
+ + EGRU225D DUXFORD RWY 06R + 520334N 0000352E -
520401N 0000325E -
520437N 0000456E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520409N 0000524E -
520334N 0000352E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.06455875,52.05945183330001,609.6 0.08995541669999998,52.06923894439999,609.6 0.08701042639999999,52.0716326258,609.6 0.0844272855,52.07418010829999,609.6 0.0822270556,52.0768606667,609.6 0.0568375833,52.0670756667,609.6 0.06455875,52.05945183330001,609.6 + + + + +
+ + EGRU225E DUXFORD RWY 24L + 520716N 0001150E -
520648N 0001218E -
520615N 0001051E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520642N 0001023E -
520716N 0001150E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1973161944,52.1210931389,609.6 0.1730776667,52.1117941389,609.6 0.1760220254,52.1093989495,609.6 0.1786034196,52.1068500334,609.6 0.1808008611,52.1041681667,609.6 0.2050466944,52.11346938890001,609.6 0.1973161944,52.1210931389,609.6 + + + + +
+ + EGRU226A CAMBRIDGE + A circle, 2.5 NM radius, centred at 521218N 0001030E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.175,52.2466098839,609.6 0.1687452292,52.2464322185,609.6 0.1625439707,52.2459007422,609.6 0.1564492751,52.2450200018,609.6 0.1505132739,52.2437975319,609.6 0.1447867299,52.2422437896,609.6 0.1393186007,52.2403720645,609.6 0.1341556167,52.2381983642,609.6 0.1293418805,52.2357412764,609.6 0.1249184884,52.2330218089,609.6 0.1209231787,52.23006320870001,609.6 0.1173900105,52.2268907621,609.6 0.1143490731,52.2235315779,609.6 0.111826232,52.2200143539,609.6 0.1098429104,52.2163691314,609.6 0.10841591,52.2126270374,609.6 0.1075572719,52.2088200185,609.6 0.1072741782,52.2049805669,609.6 0.1075688958,52.2011414438,609.6 0.108438762,52.1973353987,609.6 0.1098762123,52.1935948911,609.6 0.1118688498,52.1899518133,609.6 0.1143995555,52.1864372194,609.6 0.1174466383,52.18308106089999,609.6 0.1209840236,52.179911933,609.6 0.1249814783,52.176956831,609.6 0.1294048705,52.1742409224,609.6 0.1342164617,52.1717873329,609.6 0.1393752286,52.1696169512,609.6 0.1448372124,52.1677482519,609.6 0.1505558918,52.1661971396,609.6 0.1564825772,52.1649768144,609.6 0.1625668229,52.16409766040001,609.6 0.1687568532,52.163567158,609.6 0.175,52.163389821,609.6 0.1812431468,52.163567158,609.6 0.1874331771,52.16409766040001,609.6 0.1935174228,52.1649768144,609.6 0.1994441082,52.1661971396,609.6 0.2051627876,52.1677482519,609.6 0.2106247714,52.1696169512,609.6 0.2157835383,52.1717873329,609.6 0.2205951295,52.1742409224,609.6 0.2250185217,52.176956831,609.6 0.2290159764,52.179911933,609.6 0.2325533617,52.18308106089999,609.6 0.2356004445,52.1864372194,609.6 0.2381311502,52.1899518133,609.6 0.2401237877,52.1935948911,609.6 0.241561238,52.1973353987,609.6 0.2424311042,52.2011414438,609.6 0.2427258218,52.2049805669,609.6 0.2424427281,52.2088200185,609.6 0.24158409,52.2126270374,609.6 0.2401570896,52.2163691314,609.6 0.238173768,52.2200143539,609.6 0.2356509269,52.2235315779,609.6 0.2326099895,52.2268907621,609.6 0.2290768213,52.23006320870001,609.6 0.2250815116,52.2330218089,609.6 0.2206581195,52.2357412764,609.6 0.2158443833,52.2381983642,609.6 0.2106813993,52.2403720645,609.6 0.2052132701,52.2422437896,609.6 0.1994867261,52.2437975319,609.6 0.1935507249,52.2450200018,609.6 0.1874560293,52.2459007422,609.6 0.1812547708,52.2464322185,609.6 0.175,52.2466098839,609.6 + + + + +
+ + EGRU226B CAMBRIDGE RWY 05 + 521006N 0000655E -
521030N 0000621E -
521055N 0000708E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521030N 0000742E -
521006N 0000655E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1152138889,52.1682055556,609.6 0.1281993889,52.1749323889,609.6 0.1247950609,52.1770828876,609.6 0.1216513551,52.17937854459999,609.6 0.1187846389,52.1818074444,609.6 0.1058055556,52.1750833333,609.6 0.1152138889,52.1682055556,609.6 + + + + +
+ + EGRU226C CAMBRIDGE RWY 23 + 521432N 0001409E -
521407N 0001442E -
521341N 0001352E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521406N 0001319E -
521432N 0001409E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2357,52.24222222220001,609.6 0.2218291389,52.23506925,609.6 0.2252353881,52.2329176763,609.6 0.2283799158,52.2306208904,609.6 0.2312463889,52.2281908611,609.6 0.245125,52.2353472222,609.6 0.2357,52.24222222220001,609.6 + + + + +
+ + EGRU226D CAMBRIDGE RWY 05G + 521015N 0000728E -
521039N 0000654E -
521049N 0000713E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521026N 0000749E -
521015N 0000728E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1243861111,52.1707,609.6 0.13028475,52.1737569444,609.6 0.1267348617,52.1758197269,609.6 0.1234358833,52.17803445490001,609.6 0.120405,52.1803896111,609.6 0.114975,52.177575,609.6 0.1243861111,52.1707,609.6 + + + + +
+ + EGRU226E CAMBRIDGE RWY 23G + 521426N 0001413E -
521402N 0001447E -
521336N 0001358E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521402N 0001326E -
521426N 0001413E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2369527778,52.2406555556,609.6 0.2237949167,52.2338656944,609.6 0.2270582421,52.2316275242,609.6 0.2300497493,52.22925054540001,609.6 0.2327538611,52.22674716669999,609.6 0.2463805556,52.2337777778,609.6 0.2369527778,52.2406555556,609.6 + + + + +
+ + EGRU227A MILDENHALL + A circle, 2.5 NM radius, centred at 522143N 0002911E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4864055555999999,52.40354210509999,609.6 0.4801286155,52.4033644435,609.6 0.4739053782,52.40283297860001,609.6 0.4677890832,52.40195225730001,609.6 0.4618320474,52.4007298139,609.6 0.4560852142999999,52.39917610559999,609.6 0.4505977154,52.39730442180001,609.6 0.4454164473,52.39513077019999,609.6 0.4405856688,52.39267373810001,609.6 0.4361466218999999,52.389954333,609.6 0.4321371786,52.38699580189999,609.6 0.4285915182,52.38382343070001,609.6 0.4255398363,52.38046432760001,609.6 0.423008089,52.3769471901,609.6 0.4210177748,52.3733020589,609.6 0.4195857539,52.3695600605,609.6 0.4187241089,52.36575314049999,609.6 0.4184400464,52.3619137907,609.6 0.4187358401,52.35807477110001,609.6 0.4196088168,52.3542688306,609.6 0.421051384,52.35052842750001,609.6 0.4230511001,52.3468854532,609.6 0.4255907844,52.3433709608,609.6 0.4286486685,52.3400149007,609.6 0.4321985849,52.336845867,609.6 0.4362101930000001,52.333890854,609.6 0.4406492399,52.3311750281,609.6 0.4454778536,52.3287215143,609.6 0.4506548658,52.3265512,609.6 0.4561361626,52.3246825593,609.6 0.4618750585,52.323131496,609.6 0.4678226925,52.3219112096,609.6 0.4739284412000001,52.32103208360001,609.6 0.4801403466999999,52.3205015982,609.6 0.4864055555999999,52.32032426680001,609.6 0.4926707644,52.3205015982,609.6 0.4988826699,52.32103208360001,609.6 0.5049884186,52.3219112096,609.6 0.5109360526,52.323131496,609.6 0.5166749486,52.3246825593,609.6 0.5221562453,52.3265512,609.6 0.5273332576,52.3287215143,609.6 0.5321618712,52.3311750281,609.6 0.5366009181,52.333890854,609.6 0.5406125262,52.336845867,609.6 0.5441624426,52.3400149007,609.6 0.5472203267,52.3433709608,609.6 0.5497600110999999,52.3468854532,609.6 0.5517597271,52.35052842750001,609.6 0.5532022944,52.3542688306,609.6 0.554075271,52.35807477110001,609.6 0.5543710647,52.3619137907,609.6 0.5540870022,52.36575314049999,609.6 0.5532253572,52.3695600605,609.6 0.5517933363,52.3733020589,609.6 0.5498030221,52.3769471901,609.6 0.5472712748,52.38046432760001,609.6 0.5442195929,52.38382343070001,609.6 0.5406739325,52.38699580189999,609.6 0.5366644892,52.389954333,609.6 0.5322254424,52.39267373810001,609.6 0.5273946639,52.39513077019999,609.6 0.5222133957,52.39730442180001,609.6 0.5167258968,52.39917610559999,609.6 0.5109790637,52.4007298139,609.6 0.5050220278999999,52.40195225730001,609.6 0.4989057329,52.40283297860001,609.6 0.4926824956,52.4033644435,609.6 0.4864055555999999,52.40354210509999,609.6 + + + + +
+ + EGRU227B MILDENHALL RWY 11 + 522215N 0002335E -
522246N 0002348E -
522233N 0002520E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to
522201N 0002508E -
522215N 0002335E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3931852499999999,52.37075433329999,609.6 0.41895225,52.3670513611,609.6 0.4197280497,52.3700143536,609.6 0.420850861,52.3729354022,609.6 0.4223148889,52.3757993056,609.6 0.39655725,52.37950097220001,609.6 0.3931852499999999,52.37075433329999,609.6 + + + + +
+ + EGRU227C MILDENHALL RWY 29 + 522111N 0003446E -
522040N 0003434E -
522053N 0003302E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to
522124N 0003314E -
522111N 0003446E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5795797222,52.3530635,609.6 0.5538478610999999,52.3567994722,609.6 0.5530659598,52.3538371034,609.6 0.5519375386000001,52.3509169327,609.6 0.5504685278,52.3480541389,609.6 0.5762097222,52.3443168611,609.6 0.5795797222,52.3530635,609.6 + + + + +
+ + EGRU228A MARHAM + A circle, 2.5 NM radius, centred at 523854N 0003302E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5505555556,52.68994007980001,609.6 0.5442376252,52.6897624251,609.6 0.5379737499,52.6892309809,609.6 0.5318175182,52.68835029409999,609.6 0.5258215902,52.6871278989,609.6 0.5200372433,52.6855742523,609.6 0.5145139307,52.68370264370001,609.6 0.5092988557,52.6815290804,609.6 0.5044365668,52.6790721494,609.6 0.4999685750999999,52.67635285800001,609.6 0.4959329997,52.6733944524,609.6 0.4923642421,52.6702222182,609.6 0.4892926942,52.6668632627,609.6 0.4867444802,52.66334628249999,609.6 0.4847412373000001,52.6597013175,609.6 0.4832999341,52.655959493,609.6 0.4824327301,52.6521527532,609.6 0.4821468767,52.6483135886,609.6 0.4824446604,52.6444747577,609.6 0.4833233885,52.6406690077,609.6 0.4847754171,52.6369287951,609.6 0.4867882214,52.6332860095,609.6 0.4893445071999999,52.629771702,609.6 0.4924223626,52.6264158213,609.6 0.4959954484,52.6232469594,609.6 0.5000332253999999,52.6202921087,609.6 0.5045012171,52.6175764338,609.6 0.5093613044999999,52.6151230578,609.6 0.5145720512,52.6129528667,609.6 0.5200890564,52.61108433289999,609.6 0.5258653315,52.609533359,609.6 0.531851698,52.6083131433,609.6 0.5379972043,52.6074340684,609.6 0.5442495556,52.606903614,609.6 0.5505555556,52.606726293,609.6 0.5568615555999999,52.606903614,609.6 0.5631139068,52.6074340684,609.6 0.5692594130999999,52.6083131433,609.6 0.5752457796,52.609533359,609.6 0.5810220547,52.61108433289999,609.6 0.5865390599,52.6129528667,609.6 0.5917498066,52.6151230578,609.6 0.596609894,52.6175764338,609.6 0.6010778857,52.6202921087,609.6 0.6051156626999999,52.6232469594,609.6 0.6086887485,52.6264158213,609.6 0.6117666039,52.629771702,609.6 0.6143228897,52.6332860095,609.6 0.616335694,52.6369287951,609.6 0.6177877226,52.6406690077,609.6 0.6186664507,52.6444747577,609.6 0.6189642344,52.6483135886,609.6 0.6186783810000001,52.6521527532,609.6 0.617811177,52.655959493,609.6 0.6163698738,52.6597013175,609.6 0.6143666309,52.66334628249999,609.6 0.6118184169999999,52.6668632627,609.6 0.608746869,52.6702222182,609.6 0.6051781114,52.6733944524,609.6 0.601142536,52.67635285800001,609.6 0.5966745443,52.6790721494,609.6 0.5918122554,52.6815290804,609.6 0.5865971804,52.68370264370001,609.6 0.5810738678,52.6855742523,609.6 0.5752895209,52.6871278989,609.6 0.5692935929,52.68835029409999,609.6 0.5631373613,52.6892309809,609.6 0.5568734859,52.6897624251,609.6 0.5505555556,52.68994007980001,609.6 + + + + +
+ + EGRU228B MARHAM RWY 01 + 523538N 0003307E -
523543N 0003215E -
523626N 0003225E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
523625N 0003319E -
523538N 0003307E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5520111111,52.5939194444,609.6 0.5552008333,52.6068224167,609.6 0.5502455031,52.60672673409999,609.6 0.5452918019,52.60684977660001,609.6 0.5403657222,52.60719091669999,609.6 0.5374194444,52.5952555556,609.6 0.5520111111,52.5939194444,609.6 + + + + +
+ + EGRU228C MARHAM RWY 19 + 524200N 0003348E -
524156N 0003441E -
524114N 0003430E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
524122N 0003339E -
524200N 0003348E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5633555555999999,52.70009722219999,609.6 0.5607228889,52.6894784167,609.6 0.5656053044,52.68892168020001,609.6 0.5704082912,52.6881511361,609.6 0.5751065,52.68717083330001,609.6 0.5779833333,52.6987583333,609.6 0.5633555555999999,52.70009722219999,609.6 + + + + +
+ + EGRU228D MARHAM RWY 06 + 523643N 0002837E -
523710N 0002807E -
523743N 0002925E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
523716N 0002956E -
523643N 0002837E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.476925,52.6119888889,609.6 0.4987624167,52.62116350000001,609.6 0.4956781358,52.6235043234,609.6 0.4928787707,52.6259742675,609.6 0.4903788889,52.6285605,609.6 0.46855,52.6193888889,609.6 0.476925,52.6119888889,609.6 + + + + +
+ + EGRU228E MARHAM RWY 24 + 524104N 0003727E -
524038N 0003757E -
524005N 0003639E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
524032N 0003609E -
524104N 0003727E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6240777778,52.6845638889,609.6 0.6023875,52.6754983333,609.6 0.6054717452,52.6731559687,609.6 0.6082699432000001,52.6706845186,609.6 0.6107675833,52.6680968611,609.6 0.6324694444,52.6771666667,609.6 0.6240777778,52.6845638889,609.6 + + + + +
+ + EGRU229A LAKENHEATH + A circle, 2.5 NM radius, centred at 522434N 0003340E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5610111111,52.4510112135,609.6 0.5547274249,52.450833553,609.6 0.5484974994,52.4503020916,609.6 0.5423746316,52.44942137599999,609.6 0.5364111949,52.44819894060001,609.6 0.5306581878,52.4466452426,609.6 0.5251647946,52.44477357129999,609.6 0.5199779624999999,52.4425999343,609.6 0.515141998,52.440142919,609.6 0.5106981873999999,52.4374235329,609.6 0.5066844433,52.43446502259999,609.6 0.5031349815,52.43129267409999,609.6 0.5000800299,52.4279335955,609.6 0.4975455726,52.4244164841,609.6 0.4955531305,52.42077138050001,609.6 0.4941195817999999,52.417029411,609.6 0.4932570219,52.4132225209,609.6 0.4929726646,52.4093832018,609.6 0.4932687858,52.40554421350001,609.6 0.494142709,52.4017383046,609.6 0.4955868333999999,52.3979979332,609.6 0.4975887035,52.39435499020001,609.6 0.5001311201,52.39084052839999,609.6 0.5031922911,52.3874844981,609.6 0.5067460207,52.3843154928,609.6 0.5107619356999999,52.38136050679999,609.6 0.5152057463,52.3786447059,609.6 0.52003954,52.3761912149,609.6 0.5252221043,52.3740209211,609.6 0.530709278,52.3721522981,609.6 0.5364543259,52.3706012496,609.6 0.5424083345,52.3693809749,609.6 0.5485206266,52.3685018574,609.6 0.5547391887999999,52.3679713771,609.6 0.5610111111,52.36779404749999,609.6 0.5672830334,52.3679713771,609.6 0.5735015956,52.3685018574,609.6 0.5796138877,52.3693809749,609.6 0.5855678964,52.3706012496,609.6 0.5913129442,52.3721522981,609.6 0.5968001179,52.3740209211,609.6 0.6019826822,52.3761912149,609.6 0.6068164759,52.3786447059,609.6 0.6112602866,52.38136050679999,609.6 0.6152762015,52.3843154928,609.6 0.6188299311,52.3874844981,609.6 0.6218911021,52.39084052839999,609.6 0.6244335187,52.39435499020001,609.6 0.6264353888,52.3979979332,609.6 0.6278795132,52.4017383046,609.6 0.6287534364,52.40554421350001,609.6 0.6290495576,52.4093832018,609.6 0.6287652003,52.4132225209,609.6 0.6279026404,52.417029411,609.6 0.6264690917,52.42077138050001,609.6 0.6244766497000001,52.4244164841,609.6 0.6219421923,52.4279335955,609.6 0.6188872407,52.43129267409999,609.6 0.615337779,52.43446502259999,609.6 0.6113240349,52.4374235329,609.6 0.6068802242,52.440142919,609.6 0.6020442597,52.4425999343,609.6 0.5968574276,52.44477357129999,609.6 0.5913640344,52.4466452426,609.6 0.5856110273,52.44819894060001,609.6 0.5796475906,52.44942137599999,609.6 0.5735247228,52.4503020916,609.6 0.5672947973,52.450833553,609.6 0.5610111111,52.4510112135,609.6 + + + + +
+ + EGRU229B LAKENHEATH RWY 06 + 522224N 0002916E -
522251N 0002847E -
522323N 0003004E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to
522257N 0003034E -
522224N 0002916E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4878663333,52.3733966389,609.6 0.5093056111000001,52.38236897220001,609.6 0.5062544483,52.38471822310001,609.6 0.5034876038,52.3871958535,609.6 0.5010195,52.389789,609.6 0.4795878056,52.3808191667,609.6 0.4878663333,52.3733966389,609.6 + + + + +
+ + EGRU229C LAKENHEATH RWY 24 + 522643N 0003803E -
522617N 0003833E -
522544N 0003716E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to
522611N 0003646E -
522643N 0003803E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6342404722,52.4453773611,609.6 0.6127547778,52.43643177780001,609.6 0.6158060476,52.43408086629999,609.6 0.6185718298,52.4316015868,609.6 0.6210377778,52.42900686109999,609.6 0.6425311111000001,52.4379549167,609.6 0.6342404722,52.4453773611,609.6 + + + + +
+ + EGRU230A WATTISHAM + A circle, 2.5 NM radius, centred at 520737N 0005719E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9554138889,52.1686382148,609.6 0.9491700573,52.16846054749999,609.6 0.9429796438999999,52.16792906549999,609.6 0.9368956062,52.1670483157,609.6 0.9309699841,52.1658258326,609.6 0.9252534515999999,52.1642720733,609.6 0.91979488,52.1624003276,609.6 0.9146409181999999,52.1602266031,609.6 0.9098355913,52.15776948760001,609.6 0.9054199238000001,52.155049989,609.6 0.9014315882,52.1520913543,609.6 0.8979045841,52.1489188703,609.6 0.8948689485,52.1455596457,609.6 0.8923505021,52.1420423786,609.6 0.8903706309,52.13839711069999,609.6 0.8889461078999999,52.1346549692,609.6 0.8880889534999999,52.130847901,609.6 0.887806338,52.1270083989,609.6 0.8881005247,52.1231692242,609.6 0.8889688560999999,52.1193631272,609.6 0.8904037816000001,52.1156225676,609.6 0.8923929263000001,52.1119794383,609.6 0.8949192016,52.1084647939,609.6 0.8979609547000001,52.1051085866,609.6 0.9014921567,52.1019394118,609.6 0.9054826276,52.0989842656,609.6 0.9098982951,52.0962683158,609.6 0.9147014867,52.09381468880001,609.6 0.9198512507,52.0916442735,609.6 0.9253037047,52.0897755451,609.6 0.9310124084,52.0882244085,609.6 0.9369287568999999,52.087004064,609.6 0.9430023922,52.0861248961,609.6 0.9491816283999999,52.0855943853,609.6 0.9554138889,52.0854170454,609.6 0.9616461494,52.0855943853,609.6 0.9678253855999999,52.0861248961,609.6 0.9738990208,52.087004064,609.6 0.9798153694,52.0882244085,609.6 0.9855240730999999,52.0897755451,609.6 0.9909765270999999,52.0916442735,609.6 0.9961262910000002,52.09381468880001,609.6 1.0009294826,52.0962683158,609.6 1.0053451502,52.0989842656,609.6 1.0093356211,52.1019394118,609.6 1.0128668231,52.1051085866,609.6 1.0159085762,52.1084647939,609.6 1.0184348515,52.1119794383,609.6 1.0204239962,52.1156225676,609.6 1.0218589216,52.1193631272,609.6 1.0227272531,52.1231692242,609.6 1.0230214398,52.1270083989,609.6 1.0227388243,52.130847901,609.6 1.0218816699,52.1346549692,609.6 1.0204571469,52.13839711069999,609.6 1.0184772757,52.1420423786,609.6 1.0159588292,52.1455596457,609.6 1.0129231937,52.1489188703,609.6 1.0093961896,52.1520913543,609.6 1.005407854,52.155049989,609.6 1.0009921865,52.15776948760001,609.6 0.9961868596,52.1602266031,609.6 0.9910328978,52.1624003276,609.6 0.9855743262,52.1642720733,609.6 0.9798577937,52.1658258326,609.6 0.9739321716,52.1670483157,609.6 0.9678481339,52.16792906549999,609.6 0.9616577205,52.16846054749999,609.6 0.9554138889,52.1686382148,609.6 + + + + +
+ + EGRU230B WATTISHAM RWY 05 + 520513N 0005340E -
520537N 0005305E -
520609N 0005402E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520545N 0005438E -
520513N 0005340E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8945785833,52.08708213889999,609.6 0.9104756667,52.09594825,609.6 0.9069544023,52.0980224587,609.6 0.9036846797,52.10024747229999,609.6 0.9006835277999999,52.10261175,609.6 0.8847938611,52.0937486944,609.6 0.8945785833,52.08708213889999,609.6 + + + + +
+ + EGRU230C WATTISHAM RWY 23 + 521004N 0010104E -
520940N 0010139E -
520905N 0010037E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520929N 0010001E -
521004N 0010104E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0178328056,52.16778141670001,609.6 1.0003954167,52.1581005278,609.6 1.0039183892,52.1560243877,609.6 1.0071885817,52.15379737890001,609.6 1.010189,52.1514311111,609.6 1.0276337778,52.1611149444,609.6 1.0178328056,52.16778141670001,609.6 + + + + +
+ + EGRU231A OLD BUCKENHAM + A circle, 2 NM radius, centred at 522951N 0010307E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0520222222,52.5308612731,609.6 1.0464101911,52.5306847192,609.6 1.0408577828,52.5301569332,609.6 1.0354239821,52.5292835223,609.6 1.0301665059,52.5280737648,609.6 1.0251411855,52.5265405113,609.6 1.0204013713,52.5247000473,609.6 1.0159973633,52.5225719192,609.6 1.0119758757,52.5201787251,609.6 1.0083795406,52.51754587420001,609.6 1.0052464557,52.5147013154,609.6 1.0026097816,52.5116752395,609.6 1.0004973925,52.5084997572,609.6 0.9989315839,52.5052085578,609.6 0.9979288401999999,52.5018365507,609.6 0.9974996651,52.4984194941,609.6 0.9976484752999999,52.494993616,609.6 0.9983735593,52.49159522939999,609.6 0.9996671014000001,52.4882603475,609.6 1.00151527,52.4850243027,609.6 1.0038983689,52.48192137259999,609.6 1.0067910512,52.47898441779999,609.6 1.0101625908,52.47624453499999,609.6 1.0139772115,52.47373072850001,609.6 1.0181944671,52.4714696049,609.6 1.0227696711,52.4694850923,609.6 1.0276543694,52.4677981888,609.6 1.032796852,52.46642674120001,609.6 1.0381426984,52.4653852575,609.6 1.0436353506,52.4646847541,609.6 1.0492167076,52.4643326403,609.6 1.0548277368,52.4643326403,609.6 1.0604090939,52.4646847541,609.6 1.065901746,52.4653852575,609.6 1.0712475924,52.46642674120001,609.6 1.0763900751,52.4677981888,609.6 1.0812747734,52.4694850923,609.6 1.0858499774,52.4714696049,609.6 1.090067233,52.47373072850001,609.6 1.0938818536,52.47624453499999,609.6 1.0972533933,52.47898441779999,609.6 1.1001460755,52.48192137259999,609.6 1.1025291745,52.4850243027,609.6 1.104377343,52.4882603475,609.6 1.1056708852,52.49159522939999,609.6 1.1063959692,52.494993616,609.6 1.1065447793,52.4984194941,609.6 1.1061156042,52.5018365507,609.6 1.1051128606,52.5052085578,609.6 1.1035470519,52.5084997572,609.6 1.1014346628,52.5116752395,609.6 1.0987979888,52.5147013154,609.6 1.0956649038,52.51754587420001,609.6 1.0920685687,52.5201787251,609.6 1.0880470812,52.5225719192,609.6 1.0836430731,52.5247000473,609.6 1.0789032589,52.5265405113,609.6 1.0738779385,52.5280737648,609.6 1.0686204623,52.5292835223,609.6 1.0631866617,52.5301569332,609.6 1.0576342533,52.5306847192,609.6 1.0520222222,52.5308612731,609.6 + + + + +
+ + EGRU231B OLD BUCKENHAM RWY 02 + 522715N 0010159E -
522726N 0010110E -
522806N 0010133E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522755N 0010223E -
522715N 0010159E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0331583333,52.4542777778,609.6 1.0395878889,52.4651658333,609.6 1.0348536529,52.4659820364,609.6 1.0302589954,52.4670554677,609.6 1.0258412778,52.4683773889,609.6 1.0193194444,52.4573277778,609.6 1.0331583333,52.4542777778,609.6 + + + + +
+ + EGRU231C OLD BUCKENHAM RWY 20 + 523242N 0010416E -
523231N 0010506E -
523138N 0010435E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523149N 0010345E -
523242N 0010416E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0711527778,52.5449833333,609.6 1.0624254444,52.5302505833,609.6 1.0672134848,52.5295449608,609.6 1.0718775255,52.52857877249999,609.6 1.0763795,52.5273598889,609.6 1.0850166667,52.5419333333,609.6 1.0711527778,52.5449833333,609.6 + + + + +
+ + EGRU231D OLD BUCKENHAM RWY 07 + 522822N 0005900E -
522851N 0005837E -
522915N 0010000E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522846N 0010023E -
522822N 0005900E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9833472222,52.47273333329999,609.6 1.0063476944,52.4793926667,609.6 1.003847467,52.4819797884,609.6 1.0017391739,52.4846939569,609.6 1.0000400278,52.4875130833,609.6 0.9770555556000001,52.4808583333,609.6 0.9833472222,52.47273333329999,609.6 + + + + +
+ + EGRU231E OLD BUCKENHAM RWY 25 + 523120N 0010715E -
523051N 0010737E -
523027N 0010615E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523057N 0010552E -
523120N 0010715E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1207472222,52.5223555556,609.6 1.0977450556,52.51572966669999,609.6 1.1002399859,52.5131402516,609.6 1.1023418593,52.5104241196,609.6 1.1040336389,52.50760341669999,609.6 1.12705,52.5142333333,609.6 1.1207472222,52.5223555556,609.6 + + + + +
+ + EGRU231F OLD BUCKENHAM RWY 07L + 522828N 0005916E -
522857N 0005853E -
522917N 0005959E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522847N 0010021E -
522828N 0005916E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9878055556000001,52.4744638889,609.6 1.0059615,52.4797591944,609.6 1.0035164819,52.4823666245,609.6 1.0014662454,52.485097998,609.6 0.9998275556,52.4879310833,609.6 0.9814722222,52.4825777778,609.6 0.9878055556000001,52.4744638889,609.6 + + + + +
+ + EGRU231G OLD BUCKENHAM RWY 25R + 523122N 0010711E -
523053N 0010734E -
523030N 0010613E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523059N 0010550E -
523122N 0010711E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1198027778,52.5228194444,609.6 1.0971755833,52.51625308330001,609.6 1.0997504044,52.5136926291,609.6 1.1019361107,52.51100094609999,609.6 1.1037149444,52.5081999722,609.6 1.1261416667,52.5147083333,609.6 1.1198027778,52.5228194444,609.6 + + + + +
+ + EGRU232A NORWICH + A circle, 2.5 NM radius, centred at 524033N 0011658E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.2826638889,52.7175398849,609.6 1.2763419716,52.7173622309,609.6 1.2700741436,52.7168307887,609.6 1.2639140275,52.7159501052,609.6 1.2579143166,52.71472771460001,609.6 1.252126321,52.713174074,609.6 1.2465995249,52.7113024726,609.6 1.2413811617,52.7091289177,609.6 1.236515808,52.7066719965,609.6 1.232045001,52.703952716,609.6 1.2280068838,52.7009943225,609.6 1.2244358797,52.6978221014,609.6 1.2213623995,52.6944631601,609.6 1.218812584,52.6909461951,609.6 1.2168080836,52.687301246,609.6 1.2153658776,52.6835594382,609.6 1.2144981329,52.6797527158,609.6 1.2142121053,52.675913569,609.6 1.2145100826,52.6720747562,609.6 1.2153893702,52.6682690245,609.6 1.216842319,52.6645288303,609.6 1.2188563964,52.66088606289999,609.6 1.2214142969,52.6573717732,609.6 1.2244940948,52.6540159098,609.6 1.2280694342,52.6508470644,609.6 1.2321097566,52.6478922294,609.6 1.2365805636,52.64517656900001,609.6 1.2414437122,52.6427232063,609.6 1.2466577401,52.6405530271,609.6 1.2521782185,52.6386845036,609.6 1.2579581291,52.6371335382,609.6 1.263948263,52.6359133293,609.6 1.2700976362,52.63503425940001,609.6 1.2763539214,52.634503808,609.6 1.2826638889,52.6343264879,609.6 1.2889738564,52.634503808,609.6 1.2952301415,52.63503425940001,609.6 1.3013795148,52.6359133293,609.6 1.3073696486,52.6371335382,609.6 1.3131495593,52.6386845036,609.6 1.3186700377,52.6405530271,609.6 1.3238840656,52.6427232063,609.6 1.3287472142,52.64517656900001,609.6 1.3332180212,52.6478922294,609.6 1.3372583436,52.6508470644,609.6 1.3408336829,52.6540159098,609.6 1.3439134809,52.6573717732,609.6 1.3464713814,52.66088606289999,609.6 1.3484854587,52.6645288303,609.6 1.3499384076,52.6682690245,609.6 1.3508176951,52.6720747562,609.6 1.3511156725,52.675913569,609.6 1.3508296449,52.6797527158,609.6 1.3499619002,52.6835594382,609.6 1.3485196942,52.687301246,609.6 1.3465151938,52.6909461951,609.6 1.3439653783,52.6944631601,609.6 1.3408918981,52.6978221014,609.6 1.337320894,52.7009943225,609.6 1.3332827768,52.703952716,609.6 1.3288119698,52.7066719965,609.6 1.323946616,52.7091289177,609.6 1.3187282529,52.7113024726,609.6 1.3132014568,52.713174074,609.6 1.3074134611,52.71472771460001,609.6 1.3014137503,52.7159501052,609.6 1.2952536342,52.7168307887,609.6 1.2889858062,52.7173622309,609.6 1.2826638889,52.7175398849,609.6 + + + + +
+ + EGRU232B NORWICH RWY 09 + 524015N 0011143E -
524047N 0011142E -
524048N 0011252E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to
524015N 0011253E -
524015N 0011143E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1952277778,52.67074722220001,609.6 1.2147172778,52.6709072222,609.6 1.2142956962,52.6738970556,609.6 1.2142297104,52.67689758249999,609.6 1.2145197222,52.6798931944,609.6 1.1950472222,52.6797333333,609.6 1.1952277778,52.67074722220001,609.6 + + + + +
+ + EGRU232C NORWICH RWY 27 + 524052N 0012212E -
524019N 0012213E -
524019N 0012103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to
524051N 0012102E -
524052N 0012212E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3700972222,52.6810555556,609.6 1.3506258889,52.68092125,609.6 1.3510383033,52.6779309394,609.6 1.3510950081,52.6749303384,609.6 1.3507957778,52.6719350556,609.6 1.3702833333,52.6720694444,609.6 1.3700972222,52.6810555556,609.6 + + + + +
+ + EGRU233A CHETWYND + A circle, 2 NM radius, centred at 524842N 0022425W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4070333333,52.8448400548,609.6 -2.4126857617,52.84466350879999,609.6 -2.4182781367,52.8441357465,609.6 -2.4237510472,52.8432623748,609.6 -2.4290463597,52.84205267199999,609.6 -2.4341078399,52.8405194884,609.6 -2.4388817526,52.8386791092,609.6 -2.4433174353,52.83655108,609.6 -2.4473678374,52.83415799869999,609.6 -2.4509900203,52.8315252736,609.6 -2.4541456127,52.82868085280001,609.6 -2.4568012165,52.82565492580001,609.6 -2.4589287581,52.8224796025,609.6 -2.4605057833,52.8191885707,609.6 -2.4615156908,52.815816738,609.6 -2.4619479035,52.8123998614,609.6 -2.4617979748,52.8089741667,609.6 -2.4610676306,52.80557596489999,609.6 -2.4597647448,52.8022412674,609.6 -2.4579032504,52.7990054042,609.6 -2.4555029865,52.79590265089999,609.6 -2.452589484,52.7929658657,609.6 -2.4491936904,52.7902261431,609.6 -2.4453516401,52.78771248529999,609.6 -2.4411040699,52.7854514968,609.6 -2.4364959876,52.78346710400001,609.6 -2.4315761948,52.781780303,609.6 -2.4263967722,52.7804089394,609.6 -2.4210125304,52.7793675197,609.6 -2.4154804323,52.7786670595,609.6 -2.4098589945,52.77831496749999,609.6 -2.4042076722,52.77831496749999,609.6 -2.3985862344,52.7786670595,609.6 -2.3930541363,52.7793675197,609.6 -2.3876698944,52.7804089394,609.6 -2.3824904719,52.781780303,609.6 -2.3775706791,52.78346710400001,609.6 -2.3729625967,52.7854514968,609.6 -2.3687150266,52.78771248529999,609.6 -2.3648729763,52.7902261431,609.6 -2.3614771827,52.7929658657,609.6 -2.3585636801,52.79590265089999,609.6 -2.3561634163,52.7990054042,609.6 -2.3543019219,52.8022412674,609.6 -2.3529990361,52.80557596489999,609.6 -2.3522686919,52.8089741667,609.6 -2.3521187632,52.8123998614,609.6 -2.3525509758,52.815816738,609.6 -2.3535608834,52.8191885707,609.6 -2.3551379086,52.8224796025,609.6 -2.3572654502,52.82565492580001,609.6 -2.359921054,52.82868085280001,609.6 -2.3630766464,52.8315252736,609.6 -2.3666988293,52.83415799869999,609.6 -2.3707492314,52.83655108,609.6 -2.3751849141,52.8386791092,609.6 -2.3799588268,52.8405194884,609.6 -2.385020307,52.84205267199999,609.6 -2.3903156195,52.8432623748,609.6 -2.39578853,52.8441357465,609.6 -2.4013809049,52.84466350879999,609.6 -2.4070333333,52.8448400548,609.6 + + + + +
+ + EGRU234A HONINGTON + A circle, 2 NM radius, centred at 522036N 0004648E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7799999999999999,52.3766204797,609.6 0.7744075413000001,52.376443922,609.6 0.7688744967000001,52.3759161243,609.6 0.7634596447000001,52.375042694,609.6 0.7582205001000001,52.3738329095,609.6 0.7532126991,52.3722996215,609.6 0.7484894056000001,52.3704591158,609.6 0.7441007439000001,52.3683309388,609.6 0.7400932654999999,52.36593768910001,609.6 0.7365094537,52.3633047762,609.6 0.7333872738,52.3604601494,609.6 0.7307597713000001,52.35743399999999,609.6 0.7286547238,52.3542584394,609.6 0.7270943498,52.35096715749999,609.6 0.7260950772,52.3475950644,609.6 0.7256673738999999,52.3441779193,609.6 0.7258156422999998,52.3407519509,609.6 0.726538178,52.3373534732,609.6 0.7278271932,52.33401850060001,609.6 0.7296689055000001,52.3307823664,609.6 0.7320436881,52.3276793494,609.6 0.7349262829999998,52.3247423112,609.6 0.7382860716,52.3220023496,609.6 0.7420874025,52.31948847,609.6 0.7462899707000001,52.3172272799,609.6 0.7508492450000001,52.3152427085,609.6 0.7557169398999999,52.31355575460001,609.6 0.7608415249,52.3121842658,609.6 0.7661687685,52.3111427505,609.6 0.7716423088,52.3104422259,609.6 0.7772042465,52.3100901013,609.6 0.7827957535,52.3100901013,609.6 0.7883576912,52.3104422259,609.6 0.7938312315,52.3111427505,609.6 0.7991584750999999,52.3121842658,609.6 0.8042830600999999,52.31355575460001,609.6 0.809150755,52.3152427085,609.6 0.8137100293,52.3172272799,609.6 0.8179125975,52.31948847,609.6 0.8217139284,52.3220023496,609.6 0.825073717,52.3247423112,609.6 0.8279563119,52.3276793494,609.6 0.8303310945000001,52.3307823664,609.6 0.8321728068000002,52.33401850060001,609.6 0.833461822,52.3373534732,609.6 0.8341843577,52.3407519509,609.6 0.8343326261,52.3441779193,609.6 0.8339049227999999,52.3475950644,609.6 0.8329056502,52.35096715749999,609.6 0.8313452762,52.3542584394,609.6 0.8292402287,52.35743399999999,609.6 0.8266127262,52.3604601494,609.6 0.8234905463,52.3633047762,609.6 0.8199067345,52.36593768910001,609.6 0.8158992561,52.3683309388,609.6 0.8115105944000001,52.3704591158,609.6 0.8067873008999998,52.3722996215,609.6 0.8017794999000001,52.3738329095,609.6 0.7965403553,52.375042694,609.6 0.7911255033000001,52.3759161243,609.6 0.7855924587000001,52.376443922,609.6 0.7799999999999999,52.3766204797,609.6 + + + + +
+ + EGRU234B HONINGTON + 521947N 0004055E -
522019N 0004047E -
522035N 0004332E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to
522003N 0004340E -
521947N 0004055E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6818130278,52.3296939722,609.6 0.7278162222,52.33404155560001,609.6 0.7266595214,52.3369605969,609.6 0.7259369978,52.33993162220001,609.6 0.7256546111,52.3429304444,609.6 0.6795900833,52.3385770556,609.6 0.6818130278,52.3296939722,609.6 + + + + +
+ + EGRU234C HONINGTON + 522121N 0005151E -
522049N 0005159E -
522039N 0005004E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to
522110N 0004955E -
522121N 0005151E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8642396389,52.3559142222,609.6 0.8320553889,52.3529141111,609.6 0.8332521005999999,52.3500010766,609.6 0.8340149860999999,52.3470338347,609.6 0.8343379166999999,52.3440365556,609.6 0.8664634722,52.3470311667,609.6 0.8642396389,52.3559142222,609.6 + + + + +
+ + EGRU235 HMP BEDFORD + 520840N 0002812W -
520836N 0002756W -
520822N 0002743W -
520804N 0002758W -
520807N 0002824W -
520815N 0002840W -
520835N 0002832W -
520840N 0002812W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 115 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4699694444,52.14451944439999,182.88 -0.4754777778,52.14314722220001,182.88 -0.4778222222,52.1376055556,182.88 -0.473425,52.1351944444,182.88 -0.4660722222,52.1345444444,182.88 -0.4620055556,52.1395611111,182.88 -0.4655805556,52.1431944444,182.88 -0.4699694444,52.14451944439999,182.88 + + + + +
+ + EGRU236 HMP BIRMINGHAM + 522954N 0015626W -
522952N 0015553W -
522944N 0015547W -
522925N 0015547W -
522918N 0015558W -
522917N 0015633W -
522944N 0015648W -
522954N 0015626W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 483 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9406583333,52.4983111111,274.32 -1.9467111111,52.49555277780001,274.32 -1.9424222222,52.4879805556,274.32 -1.9326861111,52.48821944440001,274.32 -1.9296444444,52.4903972222,274.32 -1.9297361111,52.49549166669999,274.32 -1.9314527778,52.4976833333,274.32 -1.9406583333,52.4983111111,274.32 + + + + +
+ + EGRU237 HMP BURE + 524549N 0012029E -
524552N 0012052E -
524537N 0012123E -
524511N 0012049E -
524532N 0012007E -
524549N 0012029E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 77 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3413777778,52.763725,152.4 1.3352138889,52.7589055556,152.4 1.3470583333,52.7531694444,152.4 1.3564444444,52.7601555556,152.4 1.3476527778,52.7643277778,152.4 1.3413777778,52.763725,152.4 + + + + +
+ + EGRU238 HMP DOVEGATE + 525234N 0014708W -
525234N 0014639W -
525215N 0014608W -
525150N 0014649W -
525212N 0014724W -
525226N 0014723W -
525234N 0014708W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 243 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7855305556,52.876175,213.36 -1.7896972222,52.8737777778,213.36 -1.7901194444,52.869925,213.36 -1.7803777778,52.8639833333,213.36 -1.7689,52.87088333330001,213.36 -1.7776138889,52.8761416667,213.36 -1.7855305556,52.876175,213.36 + + + + +
+ + EGRU239 HMP DRAKE HALL + 525309N 0021429W -
525249N 0021352W -
525224N 0021421W -
525223N 0021445W -
525241N 0021503W -
525255N 0021453W -
525309N 0021429W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 347 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2413305556,52.8857111111,243.84 -2.2480138889,52.8818361111,243.84 -2.2509111111,52.87817500000001,243.84 -2.2458916667,52.8730916667,243.84 -2.2392972222,52.8733055556,243.84 -2.23105,52.88023888890001,243.84 -2.2413305556,52.8857111111,243.84 + + + + +
+ + EGRU240 HMP FEATHERSTONE/BRINSFORD/OAKWOOD + 523917N 0020718W -
523923N 0020623W -
523849N 0020555W -
523821N 0020609W -
523826N 0020658W -
523841N 0020716W -
523917N 0020718W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 393 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1215583333,52.6548,243.84 -2.1211027778,52.6446611111,243.84 -2.1161916667,52.64061388889999,243.84 -2.1026027778,52.63921388890001,243.84 -2.0985861111,52.6469722222,243.84 -2.1064611111,52.6564722222,243.84 -2.1215583333,52.6548,243.84 + + + + +
+ + EGRU241 HMP FIVE WELLS + 521728N 0004128W -
521727N 0004101W -
521710N 0004054W -
521646N 0004102W -
521645N 0004141W -
521658N 0004205W -
521714N 0004205W -
521728N 0004128W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 226 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6910527778,52.290975,213.36 -0.7013305556,52.2872861111,213.36 -0.7012527777999999,52.2828583333,213.36 -0.6947,52.2791583333,213.36 -0.6839666666999999,52.279475,213.36 -0.6817027778,52.2861777778,213.36 -0.6836805556,52.2908,213.36 -0.6910527778,52.290975,213.36 + + + + +
+ + EGRU242 HMP FOSSE WAY + 523531N 0010859W -
523528N 0010812W -
523443N 0010815W -
523439N 0010853W -
523446N 0010924W -
523531N 0010859W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 298 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1498138889,52.59188888890001,213.36 -1.1565666667,52.5795416667,213.36 -1.1481777778,52.5774944444,213.36 -1.1375694444,52.5785861111,213.36 -1.136575,52.5911527778,213.36 -1.1498138889,52.59188888890001,213.36 + + + + +
+ + EGRU243 HMP FOSTON HALL + 525313N 0014400W -
525314N 0014325W -
525303N 0014256W -
525237N 0014314W -
525237N 0014357W -
525313N 0014400W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 223 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.733425,52.8869805556,213.36 -1.732525,52.8769722222,213.36 -1.7205361111,52.8770083333,213.36 -1.715675,52.8840833333,213.36 -1.7236166667,52.8872555556,213.36 -1.733425,52.8869805556,213.36 + + + + +
+ + EGRU244 HMP GARTREE + 523004N 0005752W -
522959N 0005714W -
522931N 0005708W -
522921N 0005801W -
522945N 0005814W -
523004N 0005752W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 398 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.964475,52.5010833333,243.84 -0.9705583333,52.4957944444,243.84 -0.9670111111,52.4890361111,243.84 -0.9521666667000001,52.49195,243.84 -0.9539333333000001,52.4998388889,243.84 -0.964475,52.5010833333,243.84 + + + + +
+ + EGRU245 HMP HEWELL + 521951N 0015926W -
521935N 0015833W -
521911N 0015853W -
521911N 0015919W -
521917N 0015936W -
521930N 0015948W -
521951N 0015926W
Upper limit: 900 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 443 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9904305556,52.33096666670001,274.32 -1.9966583333,52.32496388890001,274.32 -1.9934444444,52.3214833333,274.32 -1.9885444444,52.3197611111,274.32 -1.9815083333,52.3198361111,274.32 -1.9757583333,52.3262611111,274.32 -1.9904305556,52.33096666670001,274.32 + + + + +
+ + EGRU246 HMP HIGHPOINT + 520847N 0003034E -
520845N 0003109E -
520801N 0003134E -
520749N 0003019E -
520822N 0003003E -
520847N 0003034E
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 390 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5095194444,52.1464944444,243.84 0.5008166667,52.1393277778,243.84 0.5051555556,52.1304,243.84 0.5260694444,52.1337222222,243.84 0.5192861111,52.1459222222,243.84 0.5095194444,52.1464944444,243.84 + + + + +
+ + EGRU247 HMP LEICESTER + 523755N 0010756W -
523744N 0010724W -
523728N 0010735W -
523721N 0010753W -
523730N 0010818W -
523749N 0010821W -
523755N 0010756W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 215 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1321138889,52.6320527778,213.36 -1.1391555556,52.63035,213.36 -1.1383638889,52.6250333333,213.36 -1.1312555556,52.62247777779999,213.36 -1.126375,52.6244472222,213.36 -1.1232083333,52.6289055556,213.36 -1.1321138889,52.6320527778,213.36 + + + + +
+ + EGRU248 HMP LITTLEHEY + 521707N 0001916W -
521706N 0001824W -
521656N 0001811W -
521637N 0001817W -
521627N 0001846W -
521633N 0001920W -
521648N 0001924W -
521707N 0001916W
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 173 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3211638889,52.2851944444,182.88 -0.3232416667,52.2799638889,182.88 -0.3221722222,52.2757138889,182.88 -0.31275,52.2740583333,182.88 -0.3047,52.2770305556,182.88 -0.3030472222,52.28208888889999,182.88 -0.3065888889,52.2849,182.88 -0.3211638889,52.2851944444,182.88 + + + + +
+ + EGRU249 HMP LONG LARTIN + 520649N 0015133W -
520643N 0015034W -
520609N 0015055W -
520616N 0015158W -
520649N 0015133W
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 160 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8592277778,52.1137055556,182.88 -1.8661638889,52.1045055556,182.88 -1.8485638889,52.10248055560001,182.88 -1.8427472222,52.1118416667,182.88 -1.8592277778,52.1137055556,182.88 + + + + +
+ + EGRU250 HMP NORWICH + 523836N 0011852E -
523838N 0011915E -
523811N 0011938E -
523801N 0011938E -
523748N 0011855E -
523753N 0011845E -
523821N 0011823E -
523836N 0011852E
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Norwich Airport (FRZ - EGRU232A) and HMPPS.
Contact online:
https://www.norwichairport.co.uk/airfield-pilot-information/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 160 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3143916667,52.643425,182.88 1.306325,52.63922777780001,182.88 1.3124305556,52.6312888889,182.88 1.315325,52.62987222219999,182.88 1.3273166667,52.6334861111,182.88 1.3273055556,52.6363027778,182.88 1.3208805556,52.6439222222,182.88 1.3143916667,52.643425,182.88 + + + + +
+ + EGRU251 HMP NOTTINGHAM + 525921N 0010935W -
525925N 0010857W -
525856N 0010848W -
525850N 0010906W -
525848N 0010942W -
525905N 0010948W -
525915N 0010946W -
525921N 0010935W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 255 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1597333333,52.9892694444,213.36 -1.1628611111,52.9873611111,213.36 -1.1632805556,52.9847805556,213.36 -1.1615972222,52.9799111111,213.36 -1.1516527778,52.98049166669999,213.36 -1.1467583333,52.9822333333,213.36 -1.1490861111,52.99026666669999,213.36 -1.1597333333,52.9892694444,213.36 + + + + +
+ + EGRU252 HMP PETERBOROUGH + 523529N 0001553W -
523535N 0001524W -
523459N 0001501W -
523451N 0001534W -
523458N 0001559W -
523506N 0001602W -
523520N 0001602W -
523529N 0001553W
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 62 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2647388889,52.5912555556,152.4 -0.2671416667,52.58887777779999,152.4 -0.2673222222,52.5848972222,152.4 -0.2662805556,52.58265277779999,152.4 -0.259575,52.58096666670001,152.4 -0.2503805556,52.5831861111,152.4 -0.2566833333,52.59310277779999,152.4 -0.2647388889,52.5912555556,152.4 + + + + +
+ + EGRU253 HMP RYE HILL/OLNEY + 522004N 0011457W -
522005N 0011435W -
521956N 0011413W -
521948N 0011408W -
521937N 0011406W -
521925N 0011421W -
521919N 0011455W -
521920N 0011535W -
522000N 0011513W -
522004N 0011457W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 361 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2492583333,52.3345611111,243.84 -1.2535833333,52.3334,243.84 -1.2598194444,52.3222833333,243.84 -1.24855,52.3219944444,243.84 -1.2393027778,52.32349166669999,243.84 -1.2349888889,52.3268305556,243.84 -1.2354277778,52.3299555556,243.84 -1.2369777778,52.3322388889,243.84 -1.2430083333,52.3347111111,243.84 -1.2492583333,52.3345611111,243.84 + + + + +
+ + EGRU254 HMP STAFFORD + 524854N 0020734W -
524902N 0020643W -
524841N 0020635W -
524828N 0020639W -
524820N 0020720W -
524854N 0020734W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 267 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1262083333,52.8149555556,213.36 -2.1221472222,52.8056,213.36 -2.1107027778,52.8076833333,213.36 -2.1095888889,52.81147500000001,213.36 -2.1118638889,52.8170972222,213.36 -2.1262083333,52.8149555556,213.36 + + + + +
+ + EGRU255 HMP STOCKEN + 524512N 0003449W -
524513N 0003414W -
524450N 0003403W -
524434N 0003430W -
524429N 0003454W -
524440N 0003514W -
524449N 0003518W -
524504N 0003516W -
524512N 0003449W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 371 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5802055556,52.75343611110001,243.84 -0.5877777778,52.75105,243.84 -0.5882805556,52.7468638889,243.84 -0.5872194444,52.74452777780001,243.84 -0.5816472222,52.7414027778,243.84 -0.5750555556,52.74279166670001,243.84 -0.5675138889,52.74725,243.84 -0.5705249999999999,52.7535111111,243.84 -0.5802055556,52.75343611110001,243.84 + + + + +
+ + EGRU256 HMP STOKE HEATH + 525231N 0023138W -
525224N 0023119W -
525231N 0023107W -
525216N 0023045W -
525202N 0023043W -
525157N 0023052W -
525142N 0023059W -
525152N 0023157W -
525231N 0023138W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by RAF Shawbury (Ternhill FRZ - EGRU206A) and HMPPS.
Contact: RAF Shawbury Station Ops 01939-250341 ext 7163 shy-ops@mod.gov.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 269 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5272138889,52.87520555559999,213.36 -2.5324694444,52.86448888890001,213.36 -2.5165222222,52.8617055556,213.36 -2.5145416667,52.865825,213.36 -2.5119222222,52.8672861111,213.36 -2.5124138889,52.87117499999999,213.36 -2.5187416667,52.87525555560001,213.36 -2.5219416667,52.87341388889999,213.36 -2.5272138889,52.87520555559999,213.36 + + + + +
+ + EGRU257 HMP SWINFEN HALL + 523936N 0014816W -
523921N 0014741W -
523908N 0014741W -
523849N 0014810W -
523857N 0014834W -
523910N 0014858W -
523936N 0014816W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 309 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8045694444,52.6599611111,243.84 -1.8159944444,52.6529083333,243.84 -1.8095166667,52.6490972222,243.84 -1.8028055556,52.6468833333,243.84 -1.794625,52.6522055556,243.84 -1.7946388889,52.65585277779999,243.84 -1.8045694444,52.6599611111,243.84 + + + + +
+ + EGRU258 HMP WARREN HILL + 520356N 0012736E -
520335N 0012812E -
520319N 0012809E -
520307N 0012727E -
520333N 0012659E -
520356N 0012736E
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 59 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.4600444444,52.06553888890001,152.4 1.449675,52.0590805556,152.4 1.4574888889,52.0519277778,152.4 1.4692555556,52.0552388889,152.4 1.4700805556,52.05961666670001,152.4 1.4600444444,52.06553888890001,152.4 + + + + +
+ + EGRU259 HMP WAYLAND + 523337N 0005103E -
523337N 0005158E -
523256N 0005158E -
523256N 0005109E -
523313N 0005056E -
523337N 0005103E
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 189 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8507277778,52.5603666667,182.88 0.8488444444,52.5535222222,182.88 0.8524499999999999,52.54898333330001,182.88 0.8659805556,52.5489666667,182.88 0.86615,52.5603555556,182.88 0.8507277778,52.5603666667,182.88 + + + + +
+ + EGRU260 HMP WHATTON + 525709N 0005519W -
525708N 0005442W -
525710N 0005428W -
525659N 0005406W -
525634N 0005402W -
525638N 0005523W -
525709N 0005519W
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 87 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9219444444,52.9525027778,152.4 -0.9229722222,52.94383333330001,152.4 -0.900525,52.9426555556,152.4 -0.9015999999999998,52.94975,152.4 -0.9076666667,52.95289166669999,152.4 -0.9117305556,52.95223055560001,152.4 -0.9219444444,52.9525027778,152.4 + + + + +
+ + EGRU261 HMP WHITEMOOR + 523445N 0000411E -
523456N 0000509E -
523421N 0000527E -
523410N 0000430E -
523445N 0000411E
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 17 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0698444444,52.5791083333,152.4 0.0748722222,52.5693833333,152.4 0.0908222222,52.5725166667,152.4 0.08574444439999999,52.58228333329999,152.4 0.0698444444,52.5791083333,152.4 + + + + +
+ + EGRU262 HMP WOODHILL + 520113N 0004826W -
520038N 0004752W -
520021N 0004838W -
520056N 0004913W -
520113N 0004826W
Upper limit: 900 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 401 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.807125,52.0203222222,274.32 -0.8203583333000001,52.01555555560001,274.32 -0.8106138888999999,52.0057194444,274.32 -0.7978666666999999,52.01063333329999,274.32 -0.807125,52.0203222222,274.32 + + + + +
+ + EGRU301A VALLEY + A circle, 2.5 NM radius, centred at 531453N 0043207W
Upper limit: 2000 FT SFC
Lower limit: 0 FT SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5353333333,53.2897691896,609.6 -4.5417394023,53.2895915492,609.6 -4.5480906587,53.2890601481,609.6 -4.5543327631,53.2881795327,609.6 -4.5604123179,53.2869572374,609.6 -4.5662773276,53.2854037189,609.6 -4.5718776474,53.28353226620001,609.6 -4.5771654137,53.281358886,609.6 -4.5820954562,53.2789021651,609.6 -4.5866256844,53.27618310959999,609.6 -4.5907174486,53.273224965,609.6 -4.5943358686,53.2700530154,609.6 -4.597450131,53.2666943668,609.6 -4.6000337501,53.2631777142,609.6 -4.6020647903,53.25953309519999,609.6 -4.6035260505,53.2557916327,609.6 -4.6044052057,53.25198526850001,609.6 -4.604694908,53.2481464901,609.6 -4.6043928434,53.2443080527,609.6 -4.6035017468,53.2405027001,609.6 -4.6020293729,53.2367628853,609.6 -4.599988425,53.23312049379999,609.6 -4.5973964418,53.2296065728,609.6 -4.5942756435,53.22625106689999,609.6 -4.5906527385,53.2230825641,609.6 -4.5865586931,53.22012805289999,609.6 -4.5820284648,53.2174126938,609.6 -4.5771007037,53.2149596063,609.6 -4.5718174223,53.2127896729,609.6 -4.5662236383,53.2109213629,609.6 -4.5603669927,53.209370576,609.6 -4.5542973456,53.2081505083,609.6 -4.548066355,53.2072715406,609.6 -4.5417270399,53.2067411509,609.6 -4.5353333333,53.2065638516,609.6 -4.5289396267,53.2067411509,609.6 -4.5226003117,53.2072715406,609.6 -4.5163693211,53.2081505083,609.6 -4.510299674,53.209370576,609.6 -4.5044430283,53.2109213629,609.6 -4.4988492444,53.2127896729,609.6 -4.493565963,53.2149596063,609.6 -4.4886382018,53.2174126938,609.6 -4.4841079736,53.22012805289999,609.6 -4.4800139281,53.2230825641,609.6 -4.4763910232,53.22625106689999,609.6 -4.4732702249,53.2296065728,609.6 -4.4706782417,53.23312049379999,609.6 -4.4686372938,53.2367628853,609.6 -4.4671649199,53.2405027001,609.6 -4.4662738233,53.2443080527,609.6 -4.4659717587,53.2481464901,609.6 -4.4662614609,53.25198526850001,609.6 -4.4671406162,53.2557916327,609.6 -4.4686018763,53.25953309519999,609.6 -4.4706329166,53.2631777142,609.6 -4.4732165356,53.2666943668,609.6 -4.4763307981,53.2700530154,609.6 -4.4799492181,53.273224965,609.6 -4.4840409822,53.27618310959999,609.6 -4.4885712105,53.2789021651,609.6 -4.4935012529,53.281358886,609.6 -4.4987890193,53.28353226620001,609.6 -4.504389339,53.2854037189,609.6 -4.5102543488,53.2869572374,609.6 -4.5163339036,53.2881795327,609.6 -4.5225760079,53.2890601481,609.6 -4.5289272644,53.2895915492,609.6 -4.5353333333,53.2897691896,609.6 + + + + +
+ + EGRU301B VALLEY RWY 01 + 531154N 0043228W -
531158N 0043322W -
531229N 0043316W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531224N 0043223W -
531154N 0043228W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5412361111,53.1983583333,609.6 -4.5397092778,53.2066468056,609.6 -4.5446913844,53.2069446068,609.6 -4.5496247792,53.2074573908,609.6 -4.5544837778,53.2081825,609.6 -4.5561083333,53.1993472222,609.6 -4.5412361111,53.1983583333,609.6 + + + + +
+ + EGRU301C VALLEY RWY 19 + 531810N 0043213W -
531806N 0043120W -
531721N 0043128W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531723N 0043222W -
531810N 0043213W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5370638889,53.3026916667,609.6 -4.5394639444,53.2896954167,609.6 -4.5344489699,53.2897658191,609.6 -4.5294386237,53.2896188347,609.6 -4.5244591389,53.28925524999999,609.6 -4.5221555556,53.3017055556,609.6 -4.5370638889,53.3026916667,609.6 + + + + +
+ + EGRU301D VALLEY RWY 13 + 531646N 0043630W -
531711N 0043555W -
531642N 0043459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531618N 0043534W -
531646N 0043630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6082879167,53.2794899167,609.6 -4.5927136389,53.2715534167,609.6 -4.5897540887,53.2739730646,609.6 -4.5865109682,53.2762584688,609.6 -4.5830011389,53.2783977222,609.6 -4.5985659167,53.2863302778,609.6 -4.6082879167,53.2794899167,609.6 + + + + +
+ + EGRU301E VALLEY RWY 31 + 531253N 0042730W -
531228N 0042805W -
531305N 0042916W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531329N 0042841W -
531253N 0042730W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4584117778,53.2147212778,609.6 -4.4780087222,53.22475830560001,609.6 -4.4809704688,53.2223411037,609.6 -4.4842144577,53.2200582086,609.6 -4.4877238056,53.2179214722,609.6 -4.4681175556,53.2078808611,609.6 -4.4584117778,53.2147212778,609.6 + + + + +
+ + EGRU302A CAERNARFON + A circle, 2 NM radius, centred at 530607N 0042015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3376138889,53.1351023087,609.6 -4.3433043386,53.1349257699,609.6 -4.3489343296,53.1343980293,609.6 -4.3544440496,53.13352469369999,609.6 -4.3597749729,53.1323150412,609.6 -4.364870486,53.1307819219,609.6 -4.3696764915,53.1289416205,609.6 -4.3741419857,53.1268136824,609.6 -4.3782196013,53.1244207048,609.6 -4.3818661114,53.12178809540001,609.6 -4.3850428872,53.1189438015,609.6 -4.3877163068,53.1159180117,609.6 -4.3898581093,53.1127428348,609.6 -4.3914456909,53.1094519572,609.6 -4.3924623404,53.1060802854,609.6 -4.3928974115,53.1026635745,609.6 -4.3927464296,53.09923804879999,609.6 -4.3920111343,53.0958400175,609.6 -4.3906994541,53.09250549,609.6 -4.3888254173,53.0892697945,609.6 -4.3864089981,53.0861672042,609.6 -4.3834758997,53.0832305756,609.6 -4.3800572789,53.0804910008,609.6 -4.3761894124,53.0779774803,609.6 -4.3719133111,53.07571661670001,609.6 -4.3672742846,53.0737323344,609.6 -4.3623214621,53.0720456282,609.6 -4.357107273,53.070674342,609.6 -4.3516868947,53.0696329815,609.6 -4.3461176715,53.0689325613,609.6 -4.3404585112,53.0685804894,609.6 -4.3347692666,53.0685804894,609.6 -4.3291101063,53.0689325613,609.6 -4.3235408831,53.0696329815,609.6 -4.3181205048,53.070674342,609.6 -4.3129063157,53.0720456282,609.6 -4.3079534931,53.0737323344,609.6 -4.3033144667,53.07571661670001,609.6 -4.2990383653,53.0779774803,609.6 -4.2951704989,53.0804910008,609.6 -4.2917518781,53.0832305756,609.6 -4.2888187797,53.0861672042,609.6 -4.2864023605,53.0892697945,609.6 -4.2845283237,53.09250549,609.6 -4.2832166435,53.0958400175,609.6 -4.2824813481,53.09923804879999,609.6 -4.2823303663,53.1026635745,609.6 -4.2827654374,53.1060802854,609.6 -4.2837820869,53.1094519572,609.6 -4.2853696685,53.1127428348,609.6 -4.2875114709,53.1159180117,609.6 -4.2901848905,53.1189438015,609.6 -4.2933616663,53.12178809540001,609.6 -4.2970081764,53.1244207048,609.6 -4.3010857921,53.1268136824,609.6 -4.3055512863,53.1289416205,609.6 -4.3103572918,53.1307819219,609.6 -4.3154528048,53.1323150412,609.6 -4.3207837282,53.13352469369999,609.6 -4.3262934482,53.1343980293,609.6 -4.3319234391,53.1349257699,609.6 -4.3376138889,53.1351023087,609.6 + + + + +
+ + EGRU302B CAERNARFON RWY 07 + 530455N 0042437W -
530525N 0042455W -
530543N 0042331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to
530512N 0042313W -
530455N 0042437W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4103138889,53.08182499999999,609.6 -4.3869033611,53.0867385278,609.6 -4.3889621559,53.0894737148,609.6 -4.3906033207,53.0923094586,609.6 -4.3918134167,53.09522269440001,609.6 -4.4152138889,53.09031111110001,609.6 -4.4103138889,53.08182499999999,609.6 + + + + +
+ + EGRU302C CAERNARFON RWY 25 + 530718N 0041554W -
530648N 0041536W -
530630N 0041700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to
530701N 0041718W -
530718N 0041554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.2648611111,53.1217694444,609.6 -4.2882921389,53.1168824722,609.6 -4.286237965,53.114145571,609.6 -4.2846023923,53.1113083851,609.6 -4.2833986667,53.10839402780001,609.6 -4.2599555556,53.1132833333,609.6 -4.2648611111,53.1217694444,609.6 + + + + +
+ + EGRU303A WOODVALE + A circle, 2 NM radius, centred at 533454N 0030327W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0575277778,53.615002394,609.6 -3.0632825546,53.6148258671,609.6 -3.0689761866,53.6142981621,609.6 -3.0745481834,53.61342488569999,609.6 -3.0799393554,53.6122153156,609.6 -3.0850924473,53.6106823016,609.6 -3.0899527491,53.608842128,609.6 -3.0944686797,53.6067143394,609.6 -3.0985923365,53.60432153210001,609.6 -3.1022800041,53.6016891128,609.6 -3.1054926184,53.5988450274,609.6 -3.108196179,53.5958194632,609.6 -3.1103621078,53.5926445269,609.6 -3.1119675482,53.5893539031,609.6 -3.1129956032,53.5859824958,609.6 -3.1134355093,53.5825660578,609.6 -3.1132827447,53.57914081059999,609.6 -3.1125390718,53.5757430602,609.6 -3.1112125119,53.572408813,609.6 -3.109317254800001,53.5691733937,609.6 -3.1068735025,53.5660710724,609.6 -3.1039072508,53.5631347019,609.6 -3.1004500096,53.5603953712,609.6 -3.096538466300001,53.5578820774,609.6 -3.092214094900001,53.55562141970001,609.6 -3.087522716300001,53.55363732,609.6 -3.0825140131,53.5519507702,609.6 -3.0772410052,53.5505796121,609.6 -3.0717594907,53.5495383493,609.6 -3.0661274586,53.54883799510001,609.6 -3.0604044788,53.5484859565,609.6 -3.0546510767,53.5484859565,609.6 -3.048928097,53.54883799510001,609.6 -3.0432960648,53.5495383493,609.6 -3.037814550299999,53.5505796121,609.6 -3.0325415424,53.5519507702,609.6 -3.0275328393,53.55363732,609.6 -3.0228414607,53.55562141970001,609.6 -3.0185170893,53.5578820774,609.6 -3.0146055459,53.5603953712,609.6 -3.011148304799999,53.5631347019,609.6 -3.0081820531,53.5660710724,609.6 -3.0057383008,53.5691733937,609.6 -3.0038430436,53.572408813,609.6 -3.0025164838,53.5757430602,609.6 -3.001772810899999,53.57914081059999,609.6 -3.0016200463,53.5825660578,609.6 -3.0020599523,53.5859824958,609.6 -3.0030880073,53.5893539031,609.6 -3.0046934478,53.5926445269,609.6 -3.0068593766,53.5958194632,609.6 -3.0095629372,53.5988450274,609.6 -3.0127755514,53.6016891128,609.6 -3.0164632191,53.60432153210001,609.6 -3.0205868758,53.6067143394,609.6 -3.0251028064,53.608842128,609.6 -3.0299631082,53.6106823016,609.6 -3.035116200200001,53.6122153156,609.6 -3.0405073722,53.61342488569999,609.6 -3.0460793689,53.6142981621,609.6 -3.051773001,53.6148258671,609.6 -3.0575277778,53.615002394,609.6 + + + + +
+ + EGRU303B WOODVALE RWY 03 + 533204N 0030543W -
533220N 0030630W -
533320N 0030531W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533304N 0030444W -
533204N 0030543W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0953566667,53.53433488889999,609.6 -3.0789983056,53.5509941389,609.6 -3.0835627936,53.5522709422,609.6 -3.0879157218,53.5537874214,609.6 -3.0920216944,53.55553125,609.6 -3.108372694399999,53.5388743611,609.6 -3.0953566667,53.53433488889999,609.6 + + + + +
+ + EGRU303C WOODVALE RWY 21 + 533745N 0030111W -
533728N 0030024W -
533628N 0030123W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533645N 0030210W -
533745N 0030111W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0196293889,53.6290938333,609.6 -3.0360356111,53.6124486667,609.6 -3.031465676,53.6111705519,609.6 -3.0271083965,53.609652509,609.6 -3.0229993056,53.6079069167,609.6 -3.0065856389,53.6245544167,609.6 -3.0196293889,53.6290938333,609.6 + + + + +
+ + EGRU303D WOODVALE RWY 08 + 533358N 0030816W -
533430N 0030825W -
533439N 0030647W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533408N 0030633W -
533358N 0030816W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1378758889,53.5660964167,609.6 -3.1091354444,53.56891102779999,609.6 -3.1108744368,53.5717451964,609.6 -3.112175241400001,53.57466145050001,609.6 -3.1130270833,53.57763583329999,609.6 -3.140312638899999,53.5749635278,609.6 -3.1378758889,53.5660964167,609.6 + + + + +
+ + EGRU303E WOODVALE RWY 26 + 533526N 0025847W -
533454N 0025838W -
533446N 0030006W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533518N 0030010W -
533526N 0025847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9796778611,53.59060158329999,609.6 -3.002726,53.58837175,609.6 -3.0019410534,53.5853908477,609.6 -3.0016131184,53.58237989359999,609.6 -3.0017448056,53.5793636389,609.6 -2.9772401944,53.5817345,609.6 -2.9796778611,53.59060158329999,609.6 + + + + +
+ + EGRU304A BLACKPOOL + A circle, 2.5 NM radius, centred at 534618N 0030143W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0286111111,53.813265525,609.6 -3.0350967314,53.813087897,609.6 -3.041526855299999,53.8125565327,609.6 -3.0478464658,53.81167597889999,609.6 -3.0540014992,53.8104537697,609.6 -3.0599393125,53.80890036139999,609.6 -3.065609135799999,53.807029043,609.6 -3.0709625102,53.8048558208,609.6 -3.0759537036,53.80239928089999,609.6 -3.080540103200001,53.79968042910001,609.6 -3.084682579699999,53.7967225097,609.6 -3.0883458215,53.7935508061,609.6 -3.0914986345,53.79019242289999,609.6 -3.0941142068,53.7866760536,609.6 -3.0961703336,53.78303173399999,609.6 -3.0976496038,53.7792905852,609.6 -3.098539543299999,53.7754845467,609.6 -3.0988327171,53.7716461032,609.6 -3.0985267866,53.7678080074,609.6 -3.0976245247,53.764003,609.6 -3.0961337862,53.76026353069999,609.6 -3.0940674357,53.7566214818,609.6 -3.0914432325,53.75310789700001,609.6 -3.088283675,53.7497527174,609.6 -3.084615805299999,53.74658452719999,609.6 -3.0804709746,53.7436303116,609.6 -3.0758845751,53.7409152277,609.6 -3.070895735700001,53.7384623916,609.6 -3.0655469893,53.7362926829,609.6 -3.0598839103,53.734424568,609.6 -3.0539547281,53.7328739443,609.6 -3.0478099183,53.7316540056,609.6 -3.0415017762,53.73077513130001,609.6 -3.0350839746,53.7302447983,609.6 -3.0286111111,53.7300675179,609.6 -3.0221382476,53.7302447983,609.6 -3.015720446,53.73077513130001,609.6 -3.0094123039,53.7316540056,609.6 -3.0032674941,53.7328739443,609.6 -2.997338311900001,53.734424568,609.6 -2.9916752329,53.7362926829,609.6 -2.986326486499999,53.7384623916,609.6 -2.981337647200001,53.7409152277,609.6 -2.9767512476,53.7436303116,609.6 -2.972606417000001,53.74658452719999,609.6 -2.9689385472,53.7497527174,609.6 -2.9657789898,53.75310789700001,609.6 -2.963154786600001,53.7566214818,609.6 -2.961088436,53.76026353069999,609.6 -2.9595976975,53.764003,609.6 -2.9586954356,53.7678080074,609.6 -2.9583895052,53.7716461032,609.6 -2.9586826789,53.7754845467,609.6 -2.9595726185,53.7792905852,609.6 -2.9610518886,53.78303173399999,609.6 -2.9631080155,53.7866760536,609.6 -2.9657235877,53.79019242289999,609.6 -2.9688764007,53.7935508061,609.6 -2.972539642500001,53.7967225097,609.6 -2.976682118999999,53.79968042910001,609.6 -2.9812685186,53.80239928089999,609.6 -2.986259712,53.8048558208,609.6 -2.991613086400001,53.807029043,609.6 -2.9972829098,53.80890036139999,609.6 -3.003220723,53.8104537697,609.6 -3.0093757564,53.81167597889999,609.6 -3.0156953669,53.8125565327,609.6 -3.0221254908,53.813087897,609.6 -3.0286111111,53.813265525,609.6 + + + + +
+ + EGRU304B BLACKPOOL RWY 10 + 534617N 0030708W -
534649N 0030704W -
534646N 0030551W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534613N 0030556W -
534617N 0030708W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1188944444,53.7713694444,609.6 -3.0987998889,53.7704148056,609.6 -3.0987721547,53.7734150578,609.6 -3.0983793941,53.7764063199,609.6 -3.097623583299999,53.7793730278,609.6 -3.1176611111,53.780325,609.6 -3.1188944444,53.7713694444,609.6 + + + + +
+ + EGRU304C BLACKPOOL RWY 28 + 534618N 0025618W -
534546N 0025622W -
534549N 0025735W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534622N 0025730W -
534618N 0025618W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.93825,53.7716805556,609.6 -2.9584088889,53.7726654167,609.6 -2.9584724548,53.769665424,609.6 -2.9589008064,53.7666759456,609.6 -2.959691638899999,53.7637125278,609.6 -2.9394777778,53.762725,609.6 -2.93825,53.7716805556,609.6 + + + + +
+ + EGRU304D BLACKPOOL RWY 13 + 534750N 0030625W -
534816N 0030552W -
534752N 0030459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534725N 0030529W -
534750N 0030625W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.106925,53.7973527778,609.6 -3.0913692778,53.7903458056,609.6 -3.0889268368,53.79298410559999,609.6 -3.0861684105,53.7955109174,609.6 -3.0831083889,53.797913,609.6 -3.097725,53.8044972222,609.6 -3.106925,53.7973527778,609.6 + + + + +
+ + EGRU304E BLACKPOOL RWY 31 + 534444N 0025801W -
534418N 0025834W -
534427N 0025854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534451N 0025817W -
534444N 0025801W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9668805556,53.7454194444,609.6 -2.9714730833,53.74749825,609.6 -2.9745715778,53.7451145435,609.6 -2.9779523219,53.7428697567,609.6 -2.9815976111,53.7407756111,609.6 -2.9760666667,53.7382722222,609.6 -2.9668805556,53.7454194444,609.6 + + + + +
+ + EGRU305A HAWARDEN + A circle, 2.5 NM radius, centred at 531041N 0025840W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9777777778,53.2196585709,609.6 -2.9841733813,53.2194809288,609.6 -2.9905142623,53.2189495226,609.6 -2.9967461703,53.21806889900001,609.6 -3.0028157954,53.2168465921,609.6 -3.0086712274,53.2152930587,609.6 -3.0142624035,53.2134215879,609.6 -3.0195415387,53.2112481864,609.6 -3.0244635363,53.2087914411,609.6 -3.0289863748,53.2060723582,609.6 -3.0330714673,53.2031141832,609.6 -3.0366839906,53.1999422005,609.6 -3.0397931814,53.19658351619999,609.6 -3.0423725966,53.1930668254,609.6 -3.044400336399999,53.1894221661,609.6 -3.0458592271,53.1856806614,609.6 -3.0467369634,53.18187425350001,609.6 -3.0470262088,53.1780354301,609.6 -3.0467246526,53.1741969468,609.6 -3.0458350247,53.1703915479,609.6 -3.0443650667,53.16665168659999,609.6 -3.0423274606,53.16300924920001,609.6 -3.0397397161,53.1594952831,609.6 -3.0366240167,53.1561397334,609.6 -3.0330070272,53.1529711887,609.6 -3.0289196629,53.1500166378,609.6 -3.0243968244,53.1473012419,609.6 -3.0194770986,53.1448481206,609.6 -3.0142024296,53.1426781572,609.6 -3.0086177621,53.140809821,609.6 -3.0027706593,53.1392590123,609.6 -2.9967109005,53.1380389272,609.6 -2.9904900599,53.13715994700001,609.6 -2.984161070499999,53.13662954979999,609.6 -2.9777777778,53.1364522479,609.6 -2.971394484999999,53.13662954979999,609.6 -2.9650654957,53.13715994700001,609.6 -2.958844655,53.1380389272,609.6 -2.9527848963,53.1392590123,609.6 -2.9469377935,53.140809821,609.6 -2.9413531259,53.1426781572,609.6 -2.936078457,53.1448481206,609.6 -2.9311587312,53.1473012419,609.6 -2.9266358927,53.1500166378,609.6 -2.9225485284,53.1529711887,609.6 -2.9189315388,53.1561397334,609.6 -2.9158158395,53.1594952831,609.6 -2.913228095,53.16300924920001,609.6 -2.9111904889,53.16665168659999,609.6 -2.9097205308,53.1703915479,609.6 -2.9088309029,53.1741969468,609.6 -2.9085293468,53.1780354301,609.6 -2.9088185922,53.18187425350001,609.6 -2.9096963285,53.1856806614,609.6 -2.911155219099999,53.1894221661,609.6 -2.9131829589,53.1930668254,609.6 -2.9157623742,53.19658351619999,609.6 -2.918871565,53.1999422005,609.6 -2.9224840883,53.2031141832,609.6 -2.9265691808,53.2060723582,609.6 -2.9310920193,53.2087914411,609.6 -2.936014016900001,53.2112481864,609.6 -2.941293152,53.2134215879,609.6 -2.9468843281,53.2152930587,609.6 -2.952739760200001,53.2168465921,609.6 -2.9588093852,53.21806889900001,609.6 -2.9650412933,53.2189495226,609.6 -2.9713821742,53.2194809288,609.6 -2.9777777778,53.2196585709,609.6 + + + + +
+ + EGRU305B HAWARDEN RWY 04 + 530811N 0030141W -
530832N 0030222W -
530859N 0030143W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to
530838N 0030102W -
530811N 0030141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.028075,53.13637500000001,609.6 -3.0172443611,53.1438768889,609.6 -3.021239603,53.1456745645,609.6 -3.025009308800001,53.1476405689,609.6 -3.0285338889,53.1497646944,609.6 -3.0393527778,53.14226944440001,609.6 -3.028075,53.13637500000001,609.6 + + + + +
+ + EGRU305C HAWARDEN RWY 22 + 531311N 0025538W -
531250N 0025457W -
531223N 0025537W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to
531244N 0025618W -
531311N 0025538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9271138889,53.2198527778,609.6 -2.938205555600001,53.21220305559999,609.6 -2.9342095663,53.21040064769999,609.6 -2.930440711300001,53.2084299101,609.6 -2.9269186111,53.2063011111,609.6 -2.9158138889,53.21395833329999,609.6 -2.9271138889,53.2198527778,609.6 + + + + +
+ + EGRU306A WARTON + A circle, 2.5 NM radius, centred at 534442N 0025300W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8834361111,53.7866240444,609.6 -2.889917622,53.7864464157,609.6 -2.8963436718,53.7859150496,609.6 -2.9026592785,53.78503449269999,609.6 -2.9088104129,53.78381227900001,609.6 -2.9147444653,53.78225886519999,609.6 -2.9204106983,53.78038754,609.6 -2.925760683500001,53.7782143098,609.6 -2.9307487181,53.7757577607,609.6 -2.935332215999999,53.7730388986,609.6 -2.9394720729,53.77008096779999,609.6 -2.9431329994,53.76690925180001,609.6 -2.946283821,53.7635508551,609.6 -2.9488977427,53.7600344714,609.6 -2.9509525737,53.75639013669999,609.6 -2.9524309136,53.752648972,609.6 -2.9533202961,53.7488429169,609.6 -2.9536132906,53.7450044565,609.6 -2.9533075598,53.7411663433,609.6 -2.9524058748,53.73736131839999,609.6 -2.950916085,53.7336218315,609.6 -2.9488510467,53.7299797653,609.6 -2.9462285079,53.72646616339999,609.6 -2.9430709527,53.7231109672,609.6 -2.9394054057,53.7199427611,609.6 -2.9352631985,53.71698853049999,609.6 -2.9306797005,53.7142734326,609.6 -2.9256940162,53.7118205837,609.6 -2.9203486515,53.70965086350001,609.6 -2.9146891521,53.70778273869999,609.6 -2.9087637168,53.7062321067,609.6 -2.902622789700001,53.7050121615,609.6 -2.896318633,53.7041332824,609.6 -2.8899048857,53.7036029465,609.6 -2.8834361111,53.7034256651,609.6 -2.8769673366,53.7036029465,609.6 -2.8705535893,53.7041332824,609.6 -2.8642494325,53.7050121615,609.6 -2.8581085054,53.7062321067,609.6 -2.8521830701,53.70778273869999,609.6 -2.846523570700001,53.70965086350001,609.6 -2.841178206,53.7118205837,609.6 -2.8361925217,53.7142734326,609.6 -2.8316090238,53.71698853049999,609.6 -2.8274668166,53.7199427611,609.6 -2.8238012695,53.7231109672,609.6 -2.8206437143,53.72646616339999,609.6 -2.8180211755,53.7299797653,609.6 -2.8159561372,53.7336218315,609.6 -2.8144663475,53.73736131839999,609.6 -2.813564662400001,53.7411663433,609.6 -2.8132589317,53.7450044565,609.6 -2.8135519261,53.7488429169,609.6 -2.8144413086,53.752648972,609.6 -2.8159196485,53.75639013669999,609.6 -2.8179744795,53.7600344714,609.6 -2.8205884012,53.7635508551,609.6 -2.8237392229,53.76690925180001,609.6 -2.8274001493,53.77008096779999,609.6 -2.8315400062,53.7730388986,609.6 -2.836123504100001,53.7757577607,609.6 -2.8411115387,53.7782143098,609.6 -2.846461524,53.78038754,609.6 -2.8521277569,53.78225886519999,609.6 -2.8580618093,53.78381227900001,609.6 -2.8642129437,53.78503449269999,609.6 -2.8705285504,53.7859150496,609.6 -2.8769546003,53.7864464157,609.6 -2.8834361111,53.7866240444,609.6 + + + + +
+ + EGRU306B WARTON RWY 07 + 534322N 0025811W -
534353N 0025828W -
534409N 0025707W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to
534339N 0025649W -
534322N 0025811W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9695861111,53.7228194444,609.6 -2.9469941389,53.72740525,609.6 -2.9489722681,53.730166133,609.6 -2.9506099817,53.7330043435,609.6 -2.9518986944,53.7359051389,609.6 -2.974475,53.7313222222,609.6 -2.9695861111,53.7228194444,609.6 + + + + +
+ + EGRU306C WARTON RWY 25 + 534602N 0024750W -
534531N 0024732W -
534515N 0024854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to
534545N 0024911W -
534602N 0024750W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7972166667,53.7671638889,609.6 -2.8198246111,53.7626105556,609.6 -2.8178532713,53.75984722719999,609.6 -2.8162233905,53.7570068727,609.6 -2.8149433889,53.7541042778,609.6 -2.7923166667,53.7586611111,609.6 -2.7972166667,53.7671638889,609.6 + + + + +
+ + EGRU307A LIVERPOOL + A circle, 2.5 NM radius, centred at 532001N 0025059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8497222222,53.3752130345,609.6 -2.8561411049,53.3750353962,609.6 -2.862505065000001,53.3745040011,609.6 -2.8687596537,53.3736233958,609.6 -2.8748513663,53.3724011146,609.6 -2.8807281029,53.3708476142,609.6 -2.8863396181,53.3689761835,609.6 -2.8916379523,53.3668028293,609.6 -2.8965778448,53.364346138,609.6 -2.901117121,53.361627116,609.6 -2.9052170537,53.3586690083,609.6 -2.9088426935,53.355497099,609.6 -2.9119631657,53.3521384939,609.6 -2.9145519318,53.3486218877,609.6 -2.916587013,53.34497731769999,609.6 -2.9180511743,53.3412359065,609.6 -2.9189320668,53.3374295957,609.6 -2.9192223284,53.333590872,609.6 -2.9189196412,53.3297524905,609.6 -2.9180267463,53.32594719439999,609.6 -2.9165514144,53.322207436,609.6 -2.9145063748,53.3185651006,609.6 -2.9119092018,53.3150512345,609.6 -2.9087821604,53.31169578200001,609.6 -2.9051520127,53.3085273302,609.6 -2.9010497869,53.3055728673,609.6 -2.896510510700001,53.3028575532,609.6 -2.8915729112,53.30040450669999,609.6 -2.8862790848,53.29823461,609.6 -2.880674139,53.29636633179999,609.6 -2.8748058092,53.2948155716,609.6 -2.868724055,53.2935955249,609.6 -2.8624806369,53.29271657250001,609.6 -2.8561286793,53.2921861921,609.6 -2.8497222222,53.2920088958,609.6 -2.8433157651,53.2921861921,609.6 -2.8369638075,53.29271657250001,609.6 -2.8307203894,53.2935955249,609.6 -2.8246386352,53.2948155716,609.6 -2.8187703055,53.29636633179999,609.6 -2.8131653596,53.29823461,609.6 -2.8078715332,53.30040450669999,609.6 -2.8029339337,53.3028575532,609.6 -2.7983946575,53.3055728673,609.6 -2.7942924318,53.3085273302,609.6 -2.7906622841,53.31169578200001,609.6 -2.7875352426,53.3150512345,609.6 -2.7849380696,53.3185651006,609.6 -2.78289303,53.322207436,609.6 -2.7814176981,53.32594719439999,609.6 -2.7805248032,53.3297524905,609.6 -2.7802221161,53.333590872,609.6 -2.7805123776,53.3374295957,609.6 -2.7813932701,53.3412359065,609.6 -2.7828574314,53.34497731769999,609.6 -2.7848925127,53.3486218877,609.6 -2.7874812787,53.3521384939,609.6 -2.7906017509,53.355497099,609.6 -2.7942273907,53.3586690083,609.6 -2.7983273235,53.361627116,609.6 -2.8028665997,53.364346138,609.6 -2.8078064921,53.3668028293,609.6 -2.8131048264,53.3689761835,609.6 -2.8187163415,53.3708476142,609.6 -2.8245930782,53.3724011146,609.6 -2.8306847907,53.3736233958,609.6 -2.8369393794,53.3745040011,609.6 -2.8433033395,53.3750353962,609.6 -2.8497222222,53.3752130345,609.6 + + + + +
+ + EGRU307B LIVERPOOL RWY 09 + 531930N 0025625W -
532002N 0025629W -
532006N 0025509W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to
531933N 0025505W -
531930N 0025625W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9402555556,53.3249333333,609.6 -2.9180339167,53.3259700278,609.6 -2.9187785016,53.3289367765,609.6 -2.9191640932,53.3319279325,609.6 -2.9191886111,53.3349279444,609.6 -2.941399999999999,53.3338916667,609.6 -2.9402555556,53.3249333333,609.6 + + + + +
+ + EGRU307C LIVERPOOL RWY 27 + 532032N 0024530W -
532000N 0024526W -
531956N 0024649W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to
532029N 0024653W -
532032N 0024530W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7584444444,53.34230277779999,609.6 -2.7814016667,53.3412629167,609.6 -2.7806603436,53.3382957709,609.6 -2.7802782982,53.3353043619,609.6 -2.7802574444,53.33230425,609.6 -2.7572916667,53.3333444444,609.6 -2.7584444444,53.34230277779999,609.6 + + + + +
+ + EGRU308A MANCHESTER + A circle, 2.5 NM radius, centred at 532113N 0021630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2749509722,53.3953507267,609.6 -2.2813728845,53.39517308880001,609.6 -2.2877398481,53.3946416951,609.6 -2.2939973885,53.3937610922,609.6 -2.3000919755,53.3925388144,609.6 -2.3059714848,53.3909853182,609.6 -2.3115856468,53.3891138927,609.6 -2.3168864796,53.38694054449999,609.6 -2.3218287009,53.38448386030001,609.6 -2.3263701163,53.38176484609999,609.6 -2.3304719804,53.3788067471,609.6 -2.3340993272,53.3756348473,609.6 -2.3372212675,53.3722762524,609.6 -2.3398112505,53.3687596571,609.6 -2.3418472871,53.3651150987,609.6 -2.3433121343,53.3613736996,609.6 -2.3441934376,53.35756740130001,609.6 -2.3444838314,53.35372869059999,609.6 -2.344180997,53.34989032229999,609.6 -2.3432876769,53.3460850394,609.6 -2.3418116456,53.3423452944,609.6 -2.3397656387,53.33870297209999,609.6 -2.3371672386,53.335189119,609.6 -2.3340387211,53.331833679,609.6 -2.330406861,53.3286652393,609.6 -2.3263027012,53.3257107877,609.6 -2.3217612858,53.32299548419999,609.6 -2.3168213602,53.3205424474,609.6 -2.3115250407,53.3183725594,609.6 -2.3059174558,53.3165042887,609.6 -2.3000463636,53.3149535347,609.6 -2.2939617469,53.3137334931,609.6 -2.2877153906,53.3128545442,609.6 -2.2813604439,53.312324166,609.6 -2.2749509722,53.3121468705,609.6 -2.2685415005,53.312324166,609.6 -2.2621865539,53.3128545442,609.6 -2.2559401975,53.3137334931,609.6 -2.2498555809,53.3149535347,609.6 -2.2439844887,53.3165042887,609.6 -2.2383769038,53.3183725594,609.6 -2.2330805842,53.3205424474,609.6 -2.2281406587,53.32299548419999,609.6 -2.2235992433,53.3257107877,609.6 -2.2194950835,53.3286652393,609.6 -2.2158632233,53.331833679,609.6 -2.2127347058,53.335189119,609.6 -2.2101363058,53.33870297209999,609.6 -2.2080902988,53.3423452944,609.6 -2.2066142676,53.3460850394,609.6 -2.2057209474,53.34989032229999,609.6 -2.2054181131,53.35372869059999,609.6 -2.2057085069,53.35756740130001,609.6 -2.2065898101,53.3613736996,609.6 -2.2080546573,53.3651150987,609.6 -2.210090694,53.3687596571,609.6 -2.2126806769,53.3722762524,609.6 -2.2158026173,53.3756348473,609.6 -2.2194299641,53.3788067471,609.6 -2.2235318281,53.38176484609999,609.6 -2.2280732435,53.38448386030001,609.6 -2.2330154648,53.38694054449999,609.6 -2.2383162976,53.3891138927,609.6 -2.2439304597,53.3909853182,609.6 -2.2498099689,53.3925388144,609.6 -2.255904556,53.3937610922,609.6 -2.2621620964,53.3946416951,609.6 -2.2685290599,53.39517308880001,609.6 -2.2749509722,53.3953507267,609.6 + + + + +
+ + EGRU308B MANCHESTER RWY 05L + 531857N 0022029W -
531922N 0022103W -
531953N 0022000W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
531928N 0021926W -
531857N 0022029W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3414111111,53.31581111109999,609.6 -2.3238734167,53.324307,609.6 -2.3273308396,53.3264781521,609.6 -2.3304832641,53.32881098330001,609.6 -2.3333465833,53.3312738611,609.6 -2.3508361111,53.3228,609.6 -2.3414111111,53.31581111109999,609.6 + + + + +
+ + EGRU308C MANCHESTER RWY 23R + 532335N 0021220W -
532310N 0021146W -
532235N 0021259W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
532300N 0021333W -
532335N 0021220W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2055305556,53.3930222222,609.6 -2.2257580556,53.3832712778,609.6 -2.2223686207,53.3810587658,609.6 -2.2192198687,53.3787240926,609.6 -2.2163605833,53.3762599167,609.6 -2.1960833333,53.38603333330001,609.6 -2.2055305556,53.3930222222,609.6 + + + + +
+ + EGRU308D MANCHESTER RWY 05R + 531801N 0022151W -
531826N 0022225W -
531942N 0021948W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
531919N 0021910W -
531801N 0022151W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3642722222,53.3002166667,609.6 -2.3194853889,53.3219233611,609.6 -2.3232527059,53.32391940340001,609.6 -2.326738245,53.3260924911,609.6 -2.3299518889,53.3284110278,609.6 -2.3736972222,53.30720555559999,609.6 -2.3642722222,53.3002166667,609.6 + + + + +
+ + EGRU309A MANCHESTER BARTON + 532618N 0022327W thence clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532749N 0022008W -
532638N 0022258W -
532618N 0022327W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3907305556,53.43829722219999,609.6 -2.3827777778,53.44388888890001,609.6 -2.3355777778,53.4635694444,609.6 -2.3343558953,53.4669212271,609.6 -2.3338295699,53.4703398171,609.6 -2.3338945616,53.473772581,609.6 -2.3345503253,53.4771831975,609.6 -2.3357900617,53.48053557090001,609.6 -2.3376007831,53.48379421360001,609.6 -2.3399634458,53.4869246223,609.6 -2.3428531463,53.4898936441,609.6 -2.3462393808,53.49266982850001,609.6 -2.3500863655,53.4952237618,609.6 -2.3543534126,53.49752838000001,609.6 -2.3589953605,53.4995592571,609.6 -2.3639630523,53.50129486489999,609.6 -2.3692038574,53.502716803,609.6 -2.3746622316,53.5038099946,609.6 -2.3802803087,53.5045628477,609.6 -2.3859985173,53.5049673785,609.6 -2.391756217,53.5050192971,609.6 -2.3974923454,53.50471805269999,609.6 -2.4031460708,53.5040668403,609.6 -2.4086574411,53.5030725655,609.6 -2.4139680243,53.5017457719,609.6 -2.4190215316,53.5001005278,609.6 -2.4237644171,53.4981542763,609.6 -2.4281464477,53.49592764920001,609.6 -2.4321212367,53.4934442471,609.6 -2.4356467354,53.490730388,609.6 -2.4386856781,53.48781482670001,609.6 -2.4412059746,53.4847284494,609.6 -2.4431810468,53.48150394459999,609.6 -2.4445901066,53.47817545670001,609.6 -2.4454183711,53.4747782227,609.6 -2.4456572136,53.4713481991,609.6 -2.4453042492,53.4679216808,609.6 -2.4443633537,53.464534917,609.6 -2.4428446174,53.4612237276,609.6 -2.4407642317,53.4580231253,609.6 -2.4381443133,53.4549669457,609.6 -2.4350126656,53.4520874903,609.6 -2.4314024809,53.4494151868,609.6 -2.4273519867,53.4469782683,609.6 -2.4229040406,53.4448024765,609.6 -2.4181056758,53.442910791,609.6 -2.4130076057,53.4413231879,609.6 -2.407663689,53.4400564305,609.6 -2.4021303634,53.4391238927,609.6 -2.3964660531,53.4385354193,609.6 -2.3907305556,53.43829722219999,609.6 + + + + +
+ + EGRU309B MANCHESTER BARTON RWY 02 + 532531N 0022405W -
532540N 0022457W -
532626N 0022437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532619N 0022344W -
532531N 0022405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.401275,53.4254111111,609.6 -2.395574,53.4384753889,609.6 -2.4005470392,53.4389250988,609.6 -2.4054320863,53.43964046000001,609.6 -2.4101894444,53.4406156667,609.6 -2.4158305556,53.42767777779999,609.6 -2.401275,53.4254111111,609.6 + + + + +
+ + EGRU309C MANCHESTER BARTON RWY 20 + 533107N 0022234W -
533059N 0022141W -
533008N 0022204W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
533016N 0022256W -
533107N 0022234W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3760861111,53.5186583333,609.6 -2.3822588889,53.5045544444,609.6 -2.3773016223,53.5040188623,609.6 -2.3724457077,53.5032188044,609.6 -2.3677307778,53.5021608056,609.6 -2.3614972222,53.51639166670001,609.6 -2.3760861111,53.5186583333,609.6 + + + + +
+ + EGRU309D MANCHESTER BARTON RWY 08L + 532741N 0022809W -
532813N 0022816W -
532820N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532748N 0022637W -
532741N 0022809W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.469125,53.46131111110001,609.6 -2.4437155833,53.4632409444,609.6 -2.4447561923,53.466179194,609.6 -2.4453488031,53.469161453,609.6 -2.4454885,53.4721634444,609.6 -2.4710111111,53.47022499999999,609.6 -2.469125,53.46131111110001,609.6 + + + + +
+ + EGRU309E MANCHESTER BARTON RWY 26R + 532856N 0021843W -
532824N 0021836W -
532817N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532850N 0022009W -
532856N 0021843W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.312025,53.4822083333,609.6 -2.3359380833,53.4804198611,609.6 -2.3348219146,53.4774914143,609.6 -2.334152951,53.4745148593,609.6 -2.3339365278,53.4715144444,609.6 -2.3101361111,53.4732944444,609.6 -2.312025,53.4822083333,609.6 + + + + +
+ + EGRU309F MANCHESTER BARTON RWY 08R + 532740N 0022805W -
532812N 0022812W -
532819N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532747N 0022637W -
532740N 0022805W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4681555556,53.46114444439999,609.6 -2.4436079722,53.4629968056,609.6 -2.4446857783,53.46592982210001,609.6 -2.4453162818,53.4689088672,609.6 -2.4454942778,53.4719096944,609.6 -2.4700277778,53.4700583333,609.6 -2.4681555556,53.46114444439999,609.6 + + + + +
+ + EGRU309G MANCHESTER BARTON RWY 26L + 532855N 0021841W -
532823N 0021834W -
532816N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532848N 0022009W -
532855N 0021841W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3112611111,53.4819472222,609.6 -2.3358037778,53.4801236111,609.6 -2.3347330633,53.47718953730001,609.6 -2.3341101379,53.4742098286,609.6 -2.3339399722,53.47120875,609.6 -2.3093833333,53.4730333333,609.6 -2.3112611111,53.4819472222,609.6 + + + + +
+ + EGRU309H MANCHESTER BARTON RWY 14 + 533006N 0022654W -
533029N 0022616W -
532956N 0022518W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532934N 0022558W -
533006N 0022654W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4483,53.5017388889,609.6 -2.4327602222,53.4927476389,609.6 -2.4293792212,53.49497990039999,609.6 -2.4256737115,53.4970209071,609.6 -2.4216739444,53.4988539444,609.6 -2.4377944444,53.5081833333,609.6 -2.4483,53.5017388889,609.6 + + + + +
+ + EGRU309I MANCHESTER BARTON RWY 32 + 532635N 0021932W -
532612N 0022010W -
532708N 0022146W -
532727N 0022101W -
532635N 0021932W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3255083333,53.44306944440001,609.6 -2.3502631944,53.4574508611,609.6 -2.3628273056,53.4522123889,609.6 -2.3359944444,53.43662777779999,609.6 -2.3255083333,53.44306944440001,609.6 + + + + +
+ + EGRU310A LEEDS BRADFORD + A circle, 2.5 NM radius, centred at 535158N 0013939W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6607694444,53.90762320009999,609.6 -1.6672696727,53.9074455742,609.6 -1.6737142792,53.90691421660001,609.6 -1.680048122,53.9060336738,609.6 -1.6862170157,53.9048114799,609.6 -1.6921681977,53.90325809139999,609.6 -1.6978507839,53.9013867969,609.6 -1.7032162058,53.89921360300001,609.6 -1.7082186283,53.8967570955,609.6 -1.7128153425,53.8940382802,609.6 -1.7169671311,53.8910804012,609.6 -1.7206386033,53.8879087416,609.6 -1.7237984952,53.884550406,609.6 -1.7264199347,53.8810340875,609.6 -1.728480668,53.8773898217,609.6 -1.7299632451,53.87364872919999,609.6 -1.7308551647,53.8698427491,609.6 -1.7311489757,53.8660043658,609.6 -1.7308423351,53.8621663314,609.6 -1.7299380227,53.858361386,609.6 -1.7284439118,53.8546219788,609.6 -1.7263728964,53.85097999159999,609.6 -1.7237427766,53.8474664672,609.6 -1.7205761018,53.8441113463,609.6 -1.7168999752,53.84094321240001,609.6 -1.712745819,53.83798905,609.6 -1.7081491048,53.83527401569999,609.6 -1.7031490498,53.8328212248,609.6 -1.6977882823,53.8306515566,609.6 -1.692112479,53.8287834768,609.6 -1.6861699773,53.8272328825,609.6 -1.6800113658,53.8260129671,609.6 -1.6736890567,53.8251341097,609.6 -1.6672568431,53.8246037868,609.6 -1.6607694444,53.8244265098,609.6 -1.6542820458,53.8246037868,609.6 -1.6478498321,53.8251341097,609.6 -1.6415275231,53.8260129671,609.6 -1.6353689116,53.8272328825,609.6 -1.6294264099,53.8287834768,609.6 -1.6237506065,53.8306515566,609.6 -1.6183898391,53.8328212248,609.6 -1.6133897841,53.83527401569999,609.6 -1.6087930699,53.83798905,609.6 -1.6046389137,53.84094321240001,609.6 -1.6009627871,53.8441113463,609.6 -1.5977961123,53.8474664672,609.6 -1.5951659925,53.85097999159999,609.6 -1.5930949771,53.8546219788,609.6 -1.5916008662,53.858361386,609.6 -1.5906965538,53.8621663314,609.6 -1.5903899132,53.8660043658,609.6 -1.5906837242,53.8698427491,609.6 -1.5915756438,53.87364872919999,609.6 -1.5930582209,53.8773898217,609.6 -1.5951189542,53.8810340875,609.6 -1.5977403937,53.884550406,609.6 -1.6009002856,53.8879087416,609.6 -1.6045717577,53.8910804012,609.6 -1.6087235464,53.8940382802,609.6 -1.6133202606,53.8967570955,609.6 -1.618322683,53.89921360300001,609.6 -1.623688105,53.9013867969,609.6 -1.6293706912,53.90325809139999,609.6 -1.6353218732,53.9048114799,609.6 -1.6414907669,53.9060336738,609.6 -1.6478246097,53.90691421660001,609.6 -1.6542692162,53.9074455742,609.6 -1.6607694444,53.90762320009999,609.6 + + + + +
+ + EGRU310B LEEDS BRADFORD RWY 14 + 535406N 0014333W -
535428N 0014253W -
535359N 0014208W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to
535337N 0014249W -
535406N 0014333W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7258722222,53.90164444440001,609.6 -1.7134789444,53.89360152779999,609.6 -1.7099776463,53.8957754389,609.6 -1.7062197951,53.89779451370001,609.6 -1.7022249444,53.8996482222,609.6 -1.7146083333,53.90768611110001,609.6 -1.7258722222,53.90164444440001,609.6 + + + + +
+ + EGRU310C LEEDS BRADFORD RWY 32 + 534948N 0013543W -
534927N 0013624W -
534957N 0013710W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to
535018N 0013629W -
534948N 0013543W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5953916667,53.8301222222,609.6 -1.6081265,53.8384270556,609.6 -1.6116280666,53.8362559837,609.6 -1.6153847414,53.834239724,609.6 -1.619377,53.83238875,609.6 -1.6066305556,53.82407777779999,609.6 -1.5953916667,53.8301222222,609.6 + + + + +
+ + EGRU311A SHERBURN-IN-ELMET + 534837N 0011510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534837N 0011510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2527638889,53.8102666667,609.6 -1.2571224026,53.80797806930001,609.6 -1.2610571872,53.8054348301,609.6 -1.2645260612,53.8026642646,609.6 -1.2674918691,53.79969612469999,609.6 -1.2699228782,53.7965622774,609.6 -1.2717931161,53.7932963613,609.6 -1.2730826444,53.789933425,609.6 -1.2737777682,53.7865095498,609.6 -1.2738711768,53.7830614618,609.6 -1.2733620161,53.779626138,609.6 -1.2722558913,53.77624040969999,609.6 -1.2705648008,53.7729405674,609.6 -1.2683070016,53.7697619731,609.6 -1.2655068083,53.7667386813,609.6 -1.2621943278,53.7639030758,609.6 -1.2584051335,53.7612855237,609.6 -1.2541798811,53.7589140514,609.6 -1.2495638721,53.75681404629999,609.6 -1.2446065683,53.75500798580001,609.6 -1.2393610627,53.7535151986,609.6 -1.2338835135,53.7523516589,609.6 -1.2282325455,53.7515298163,609.6 -1.2224686263,53.7510584638,609.6 -1.2166534236,53.7509426443,609.6 -1.2108491499,53.7511835969,609.6 -1.2051179016,53.7517787436,609.6 -1.1995209993,53.7527217173,609.6 -1.1941183362,53.7540024286,609.6 -1.1889677411,53.7556071738,609.6 -1.1841243629,53.75751877999999,609.6 -1.1796400828,53.75971678800001,609.6 -1.1755629604,53.7621776702,609.6 -1.1719367193,53.7648750804,609.6 -1.1688002784,53.7677801353,609.6 -1.1661873332,53.7708617218,609.6 -1.1641259915,53.7740868293,609.6 -1.1626384686,53.7774209021,609.6 -1.1617408441,53.7808282085,609.6 -1.1614428842,53.7842722237,609.6 -1.1617479309,53.78771602,609.6 -1.1626528599,53.79112266330001,609.6 -1.1641481077,53.79445560920001,609.6 -1.1662177682,53.7976790953,609.6 -1.168839758,53.8007585255,609.6 -1.1719860481,53.8036608427,609.6 -1.1756111111,53.8063611111,609.6 -1.2527638889,53.8102666667,609.6 + + + + +
+ + EGRU311B SHERBURN-IN-ELMET RWY 01 + 534422N 0011301W -
534426N 0011355W -
534506N 0011346W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534504N 0011251W -
534422N 0011301W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.21695,53.7393833333,609.6 -1.2141693611,53.7510245278,609.6 -1.219247129,53.7509727092,609.6 -1.2243120647,53.7511927928,609.6 -1.2293228333,53.751683,609.6 -1.2319555556,53.7406444444,609.6 -1.21695,53.7393833333,609.6 + + + + +
+ + EGRU311C SHERBURN-IN-ELMET RWY 19 + 535003N 0011234W -
534959N 0011140W -
534827N 0011202W -
534830N 0011257W -
535003N 0011234W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2095805556,53.8342722222,609.6 -1.2157734444,53.8084004444,609.6 -1.2006255278,53.8076328889,609.6 -1.1945416667,53.83301111110001,609.6 -1.2095805556,53.8342722222,609.6 + + + + +
+ + EGRU311D SHERBURN-IN-ELMET RWY 06 + 534533N 0011659W -
534601N 0011727W -
534627N 0011616W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534558N 0011553W -
534533N 0011659W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2829833333,53.7592861111,609.6 -1.2646393333,53.76597425,609.6 -1.267242897,53.76857155940001,609.6 -1.2694385055,53.771297993,609.6 -1.271208,53.77413111109999,609.6 -1.2909194444,53.7669444444,609.6 -1.2829833333,53.7592861111,609.6 + + + + +
+ + EGRU311E SHERBURN-IN-ELMET RWY 24 + 534901N 0010912W -
534834N 0010843W -
534803N 0011008W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534824N 0011054W -
534901N 0010912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1532638889,53.8170138889,609.6 -1.1817541111,53.8066739167,609.6 -1.1756111111,53.8063611111,609.6 -1.1720433532,53.80366947009999,609.6 -1.1689177222,53.80079386109999,609.6 -1.1453166667,53.8093583333,609.6 -1.1532638889,53.8170138889,609.6 + + + + +
+ + EGRU311F SHERBURN-IN-ELMET RWY 10 + 534728N 0011758W -
534759N 0011745W -
534746N 0011612W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534715N 0011625W -
534728N 0011758W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2993888889,53.7910472222,609.6 -1.2736092222,53.78744880559999,609.6 -1.2728948949,53.79042149509999,609.6 -1.2717308379,53.7933439481,609.6 -1.2701264444,53.7961923611,609.6 -1.2958916667,53.7997888889,609.6 -1.2993888889,53.7910472222,609.6 + + + + +
+ + EGRU311G SHERBURN-IN-ELMET RWY 28 + 534640N 0010821W -
534609N 0010834W -
534620N 0010955W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534652N 0010942W -
534640N 0010821W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1391666667,53.7778166667,609.6 -1.1617503611,53.7809968611,609.6 -1.1624732323,53.77802503190001,609.6 -1.1636452747,53.7751038792,609.6 -1.1652568333,53.7722571667,609.6 -1.1426583333,53.769075,609.6 -1.1391666667,53.7778166667,609.6 + + + + +
+ + EGRU311H SHERBURN-IN-ELMET RWY 10G + 534730N 0011755W -
534801N 0011743W -
534748N 0011611W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534717N 0011625W -
534730N 0011755W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2986611111,53.7915666667,609.6 -1.2734953889,53.7880835278,609.6 -1.2726844522,53.7910487701,609.6 -1.2714251173,53.7939586218,609.6 -1.2697275556,53.7967893611,609.6 -1.2951916667,53.8003138889,609.6 -1.2986611111,53.7915666667,609.6 + + + + +
+ + EGRU311I SHERBURN-IN-ELMET RWY 28G + 534643N 0010818W -
534611N 0010830W -
534623N 0010953W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534654N 0010942W -
534643N 0010818W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1383,53.77850277779999,609.6 -1.1616384444,53.7817617222,609.6 -1.1622457931,53.7787795064,609.6 -1.1633045603,53.7758418658,609.6 -1.1648060278,53.7729727222,609.6 -1.1417666667,53.7697555556,609.6 -1.1383,53.77850277779999,609.6 + + + + +
+ + EGRU312A NETHERTHORPE + A circle, 2 NM radius, centred at 531901N 0011146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1962027778,53.350214989,609.6 -1.2019218329,53.3500384556,609.6 -1.2075801243,53.349510731,609.6 -1.2131175379,53.348637422,609.6 -1.2184752531,53.3474278065,609.6 -1.2235963708,53.34589473450001,609.6 -1.2284265212,53.3440544906,609.6 -1.2329144439,53.3419266197,609.6 -1.2370125336,53.3395337186,609.6 -1.240677346,53.3369011946,609.6 -1.2438700589,53.3340569944,609.6 -1.246556882,53.33103130589999,609.6 -1.2487094133,53.327856237,609.6 -1.2503049366,53.3245654734,609.6 -1.2513266582,53.32119392039999,609.6 -1.2517638795,53.317777332,609.6 -1.251612105,53.3143519312,609.6 -1.2508730844,53.31095402610001,609.6 -1.2495547875,53.3076196243,609.6 -1.2476713144,53.30438405269999,609.6 -1.2452427405,53.3012815831,609.6 -1.2422948993,53.2983450703,609.6 -1.2388591045,53.2956056051,609.6 -1.2349718154,53.2930921862,609.6 -1.2306742488,53.2908314149,609.6 -1.2260119419,53.2888472145,609.6 -1.2210342697,53.2871605784,609.6 -1.2157939244,53.2857893497,609.6 -1.2103463594,53.28474803310001,609.6 -1.2047492055,53.2840476424,609.6 -1.1990616652,53.2836955854,609.6 -1.1933438903,53.2836955854,609.6 -1.18765635,53.2840476424,609.6 -1.1820591962,53.28474803310001,609.6 -1.1766116311,53.2857893497,609.6 -1.1713712859,53.2871605784,609.6 -1.1663936137,53.2888472145,609.6 -1.1617313067,53.2908314149,609.6 -1.1574337402,53.2930921862,609.6 -1.1535464511,53.2956056051,609.6 -1.1501106563,53.2983450703,609.6 -1.147162815,53.3012815831,609.6 -1.1447342412,53.30438405269999,609.6 -1.142850768,53.3076196243,609.6 -1.1415324711,53.31095402610001,609.6 -1.1407934505,53.3143519312,609.6 -1.1406416761,53.317777332,609.6 -1.1410788974,53.32119392039999,609.6 -1.1421006189,53.3245654734,609.6 -1.1436961423,53.327856237,609.6 -1.1458486736,53.33103130589999,609.6 -1.1485354967,53.3340569944,609.6 -1.1517282095,53.3369011946,609.6 -1.155393022,53.3395337186,609.6 -1.1594911116,53.3419266197,609.6 -1.1639790343,53.3440544906,609.6 -1.1688091847,53.34589473450001,609.6 -1.1739303024,53.3474278065,609.6 -1.1792880176,53.348637422,609.6 -1.1848254313,53.349510731,609.6 -1.1904837226,53.3500384556,609.6 -1.1962027778,53.350214989,609.6 + + + + +
+ + EGRU312B NETHERTHORPE RWY 06 + 531712N 0011522W -
531739N 0011552W -
531807N 0011445W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
531740N 0011414W -
531712N 0011522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2560277778,53.2867333333,609.6 -1.2372535278,53.294504,609.6 -1.2404625371,53.2968114135,609.6 -1.2433116277,53.2992826763,609.6 -1.2457775556,53.3018976944,609.6 -1.2645416667,53.2941305556,609.6 -1.2560277778,53.2867333333,609.6 + + + + +
+ + EGRU312C NETHERTHORPE RWY 24 + 532049N 0010813W -
532022N 0010742W -
531955N 0010848W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
532022N 0010918W -
532049N 0010813W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1368916667,53.34685555560001,609.6 -1.1551079444,53.33934775,609.6 -1.1519003867,53.3370379636,609.6 -1.1490541355,53.3345644339,609.6 -1.1465923333,53.3319473333,609.6 -1.1283666667,53.33945833329999,609.6 -1.1368916667,53.34685555560001,609.6 + + + + +
+ + EGRU312D NETHERTHORPE RWY 18 + 532146N 0011236W -
532149N 0011142W -
532101N 0011135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
532058N 0011229W -
532146N 0011236W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2100472222,53.3626888889,609.6 -1.2080307222,53.3494531667,609.6 -1.2030826375,53.3499592268,609.6 -1.1980783779,53.350196059,609.6 -1.1930588056,53.35016175,609.6 -1.1950861111,53.36350277780001,609.6 -1.2100472222,53.3626888889,609.6 + + + + +
+ + EGRU312E NETHERTHORPE RWY 36 + 531617N 0011052W -
531614N 0011146W -
531701N 0011153W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
531705N 0011059W -
531617N 0011052W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1811194444,53.2714222222,609.6 -1.1831127778,53.2845884722,609.6 -1.1880312955,53.2840134665,609.6 -1.1930161911,53.28370629,609.6 -1.1980269722,53.2836694444,609.6 -1.1960444444,53.2706083333,609.6 -1.1811194444,53.2714222222,609.6 + + + + +
+ + EGRU313A LEEDS EAST + 534837N 0011510W thence clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
534749N 0010956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534837N 0011510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2527638889,53.8102666667,609.6 -1.1756111111,53.8063611111,609.6 -1.1725646884,53.8041867195,609.6 -1.1698741737,53.8018525338,609.6 -1.16752756,53.7993918007,609.6 -1.1655416667,53.79682222219999,609.6 -1.1597722034,53.7985792559,609.6 -1.1543354207,53.8006786956,609.6 -1.1492480814,53.8030656328,609.6 -1.1445534596,53.8057197929,609.6 -1.1402915157,53.8086186276,609.6 -1.1364985567,53.8117375048,609.6 -1.1332069262,53.8150499175,609.6 -1.130444727,53.8185277071,609.6 -1.12823558,53.8221413022,609.6 -1.1265984186,53.82585996890001,609.6 -1.1255473238,53.8296520715,609.6 -1.1250913997,53.833485341,609.6 -1.1252346899,53.8373271494,609.6 -1.1259761385,53.84114478680001,609.6 -1.1273095927,53.8449057406,609.6 -1.1292238505,53.8485779722,609.6 -1.1317027504,53.8521301907,609.6 -1.1347253046,53.8555321199,609.6 -1.1382658734,53.8587547576,609.6 -1.142294381,53.8617706235,609.6 -1.1467765685,53.8645539948,609.6 -1.1516742846,53.8670811269,609.6 -1.15694581,53.86933045699999,609.6 -1.1625462135,53.8712827894,609.6 -1.1684277362,53.8729214607,609.6 -1.1745402006,53.87423248239999,609.6 -1.1808314416,53.87520466229999,609.6 -1.1872477547,53.8758296999,609.6 -1.1937343584,53.8761022585,609.6 -1.2002358655,53.8760200107,609.6 -1.2066967607,53.8755836588,609.6 -1.2130618783,53.8747969287,609.6 -1.2192768777,53.8736665375,609.6 -1.2252887108,53.87220213620001,609.6 -1.231046079,53.870416226,609.6 -1.2364998728,53.8683240512,609.6 -1.2416035943,53.8659434677,609.6 -1.2463137542,53.8632947898,609.6 -1.2505902441,53.8604006154,609.6 -1.254396678,53.8572856321,609.6 -1.2577007011,53.8539764054,609.6 -1.260474264,53.8505011509,609.6 -1.262693858,53.84688949259999,609.6 -1.2643407125,53.8431722097,609.6 -1.2654009498,53.8393809731,609.6 -1.2658656989,53.8355480755,609.6 -1.2657311656,53.8317061553,609.6 -1.2649986589,53.8278879192,609.6 -1.2636745748,53.82412586309999,609.6 -1.2617703363,53.8204519965,609.6 -1.2593022908,53.8168975701,609.6 -1.2562915665,53.8134928111,609.6 -1.2527638889,53.8102666667,609.6 + + + + +
+ + EGRU313B LEEDS EAST RWY 06 + 534803N 0011546W -
534829N 0011617W -
534851N 0011525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
534837N 0011510W -
534835N 0011429W -
534803N 0011546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2626944444,53.8007361111,609.6 -1.2413818333,53.8096936667,609.6 -1.2527638889,53.8102666667,609.6 -1.2548809198,53.8122140415,609.6 -1.25688125,53.8142020278,609.6 -1.2714694444,53.8080694444,609.6 -1.2626944444,53.8007361111,609.6 + + + + +
+ + EGRU313C LEEDS EAST RWY 24 + 535208N 0010735W -
535142N 0010703W -
535117N 0010802W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
535143N 0010834W -
535208N 0010735W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1263416667,53.8689194444,609.6 -1.1427984167,53.8620370833,609.6 -1.1395753351,53.859719205,609.6 -1.1366436064,53.85726995300001,609.6 -1.1340184722,53.8547020833,609.6 -1.11755,53.8615888889,609.6 -1.1263416667,53.8689194444,609.6 + + + + +
+ + EGRU314A DONCASTER SHEFFIELD + A circle, 2.5 NM radius, centred at 532831N 0010015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0041361111,53.51688426390001,609.6 -1.0105763852,53.51670662890001,609.6 -1.0169615527,53.5161752438,609.6 -1.0232369828,53.51529465530001,609.6 -1.0293489916,53.5140723974,609.6 -1.0352453051,53.5125189269,609.6 -1.0408755098,53.5106475327,609.6 -1.0461914861,53.5084742213,609.6 -1.0511478222,53.5060175791,609.6 -1.0557022029,53.5032986123,609.6 -1.0598157723,53.5003405657,609.6 -1.0634534648,53.4971687231,609.6 -1.0665843034,53.49381018999999,609.6 -1.0691816618,53.4902936605,609.6 -1.0712234889,53.4866491717,609.6 -1.0726924933,53.48290784560001,609.6 -1.0735762858,53.479101623,609.6 -1.073867481,53.47526299010001,609.6 -1.0735637544,53.4714247011,609.6 -1.0726678572,53.4676194985,609.6 -1.0711875872,53.46387983370001,609.6 -1.0691357169,53.460237591,609.6 -1.0665298799,53.456723816,609.6 -1.0633924162,53.4533684518,609.6 -1.0597501774,53.4502000847,609.6 -1.0556342954,53.4472457018,609.6 -1.0510799147,53.4445304622,609.6 -1.0461258912,53.4420774838,609.6 -1.0408144611,53.4399076479,609.6 -1.0351908816,53.4380394225,609.6 -1.0293030466,53.4364887065,609.6 -1.023201081,53.4352686948,609.6 -1.0169369166,53.4343897676,609.6 -1.0105638537,53.4338594025,609.6 -1.0041361111,53.4336821114,609.6 -0.9977083685,53.4338594025,609.6 -0.9913353056000002,53.4343897676,609.6 -0.9850711413,53.4352686948,609.6 -0.9789691755999999,53.4364887065,609.6 -0.9730813406,53.4380394225,609.6 -0.9674577611,53.4399076479,609.6 -0.9621463311000001,53.4420774838,609.6 -0.9571923075,53.4445304622,609.6 -0.9526379268,53.4472457018,609.6 -0.9485220448,53.4502000847,609.6 -0.9448798061,53.4533684518,609.6 -0.9417423423,53.456723816,609.6 -0.9391365054,53.460237591,609.6 -0.9370846351000001,53.46387983370001,609.6 -0.935604365,53.4676194985,609.6 -0.9347084678000002,53.4714247011,609.6 -0.9344047412999998,53.47526299010001,609.6 -0.9346959364000001,53.479101623,609.6 -0.935579729,53.48290784560001,609.6 -0.9370487333,53.4866491717,609.6 -0.9390905604000001,53.4902936605,609.6 -0.9416879189,53.49381018999999,609.6 -0.9448187574,53.4971687231,609.6 -0.9484564499000001,53.5003405657,609.6 -0.9525700193,53.5032986123,609.6 -0.9571244001,53.5060175791,609.6 -0.9620807361,53.5084742213,609.6 -0.9673967124,53.5106475327,609.6 -0.9730269171,53.5125189269,609.6 -0.9789232306000001,53.5140723974,609.6 -0.9850352394,53.51529465530001,609.6 -0.9913106695000001,53.5161752438,609.6 -0.997695837,53.51670662890001,609.6 -1.0041361111,53.51688426390001,609.6 + + + + +
+ + EGRU314B DONCASTER SHEFFIELD RWY 02 + 532512N 0010132W -
532522N 0010224W -
532614N 0010156W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to
532604N 0010105W -
532512N 0010132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0256888889,53.4200222222,609.6 -1.0179736389,53.43451025,609.6 -1.0228580729,53.4352110427,609.6 -1.0276454322,53.4361200141,609.6 -1.0323108889,53.4372324444,609.6 -1.0400194444,53.4227472222,609.6 -1.0256888889,53.4200222222,609.6 + + + + +
+ + EGRU314C DONCASTER SHEFFIELD RWY 20 + 533150N 0005857W -
533140N 0005805W -
533048N 0005833W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to
533058N 0005925W -
533150N 0005857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.982525,53.5305361111,609.6 -0.9902676110999999,53.516054,609.6 -0.9853739193,53.51535160020001,609.6 -0.9805780853,53.51444061570001,609.6 -0.9759051111,53.51332580559999,609.6 -0.9681555556,53.5278111111,609.6 -0.982525,53.5305361111,609.6 + + + + +
+ + EGRU315A RETFORD/GAMSTON + A circle, 2 NM radius, centred at 531650N 0005705W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9513888889,53.31383741539999,609.6 -0.9571030807000002,53.3136608811,609.6 -0.9627565605,53.3131331538,609.6 -0.9682892657999999,53.3122598403,609.6 -0.9736424259999999,53.3110502186,609.6 -0.9787591905,53.3095171386,609.6 -0.9835852359999999,53.30767688499999,609.6 -0.9880693455,53.3055490027,609.6 -0.9921639543,53.30315608870001,609.6 -0.995825655,53.3005235503,609.6 -0.9990156584,53.29767933420001,609.6 -1.0017002027,53.2946536287,609.6 -1.0038509099,53.2914785415,609.6 -1.0054450831,53.2881877587,609.6 -1.0064659423,53.2848161856,609.6 -1.0069027981,53.2813995765,609.6 -1.0067511584,53.2779741546,609.6 -1.0060127711,53.2745762281,609.6 -1.0046955992,53.2712418052,609.6 -1.0028137304,53.2680062126,609.6 -1.000387223,53.2649037226,609.6 -0.9974418883,53.26196719019999,609.6 -0.9940090133,53.25922770649999,609.6 -0.9901250263,53.2567142704,609.6 -0.9858311092000001,53.2544534835,609.6 -0.9811727603,53.2524692693,609.6 -0.9761993128999999,53.2507826214,609.6 -0.9709634145000001,53.2494113829,609.6 -0.9655204716,53.2483700589,609.6 -0.9599280663,53.2476696632,609.6 -0.9542453511,53.2473176037,609.6 -0.9485324267,53.2473176037,609.6 -0.9428497114000001,53.2476696632,609.6 -0.9372573062,53.2483700589,609.6 -0.9318143633000001,53.2494113829,609.6 -0.9265784649,53.2507826214,609.6 -0.9216050175000001,53.2524692693,609.6 -0.9169466686,53.2544534835,609.6 -0.9126527514,53.2567142704,609.6 -0.9087687645,53.25922770649999,609.6 -0.9053358894999999,53.26196719019999,609.6 -0.9023905548000001,53.2649037226,609.6 -0.8999640474000001,53.2680062126,609.6 -0.8980821785999999,53.2712418052,609.6 -0.8967650065999999,53.2745762281,609.6 -0.8960266193999999,53.2779741546,609.6 -0.8958749796999999,53.2813995765,609.6 -0.8963118354,53.2848161856,609.6 -0.8973326947,53.2881877587,609.6 -0.8989268679,53.2914785415,609.6 -0.9010775751,53.2946536287,609.6 -0.9037621193999998,53.29767933420001,609.6 -0.9069521226999999,53.3005235503,609.6 -0.9106138235,53.30315608870001,609.6 -0.9147084323,53.3055490027,609.6 -0.9191925418,53.30767688499999,609.6 -0.9240185872,53.3095171386,609.6 -0.9291353516999998,53.3110502186,609.6 -0.9344885119,53.3122598403,609.6 -0.9400212173,53.3131331538,609.6 -0.9456746971000001,53.3136608811,609.6 -0.9513888889,53.31383741539999,609.6 + + + + +
+ + EGRU315B RETFORD/GAMSTON RWY 03 + 531359N 0005848W -
531413N 0005937W -
531509N 0005853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to
531456N 0005804W -
531359N 0005848W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9799194443999999,53.2331333333,609.6 -0.9678115,53.2487633611,609.6 -0.9725227589,53.24977988360001,609.6 -0.9770623369,53.251046784,609.6 -0.9813933333,53.2525537778,609.6 -0.9934972222,53.23692222220001,609.6 -0.9799194443999999,53.2331333333,609.6 + + + + +
+ + EGRU315C RETFORD/GAMSTON RWY 21 + 531941N 0005522W -
531928N 0005433W -
531831N 0005517W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to
531844N 0005606W -
531941N 0005522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9227055556,53.3281666667,609.6 -0.9349966667,53.31235547219999,609.6 -0.9302773589,53.3113403148,609.6 -0.9257303104,53.3100743476,609.6 -0.9213926111,53.30856788889999,609.6 -0.9090972222,53.3243777778,609.6 -0.9227055556,53.3281666667,609.6 + + + + +
+ + EGRU316A SYERSTON + A circle, 2 NM radius, centred at 530124N 0005442W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9116666667,53.0566166392,609.6 -0.9173467706999999,53.0564400985,609.6 -0.9229665261999999,53.055912352,609.6 -0.9284662301999999,53.0550390067,609.6 -0.9337874638,53.0538293406,609.6 -0.9388737164000001,53.0522962039,609.6 -0.9436709894,53.0504558815,609.6 -0.9481283717999999,53.0483279189,609.6 -0.9521985826,53.0459349133,609.6 -0.9558384733,53.0433022727,609.6 -0.9590094850000001,53.04045794449999,609.6 -0.961678057,53.03743211769999,609.6 -0.9638159791000001,53.03425690120001,609.6 -0.9654006883,53.030965982,609.6 -0.9664155033,53.0275942667,609.6 -0.9668497966,53.0241775111,609.6 -0.9666991014000001,53.0207519397,609.6 -0.9659651533,53.01735386240001,609.6 -0.9646558661,53.014019289,609.6 -0.9627852421999998,53.0107835481,609.6 -0.9603732189,53.0076809138,609.6 -0.9574454526,53.00474424280001,609.6 -0.9540330431000001,53.0020046282,609.6 -0.9501722013,52.9994910706,609.6 -0.9459038633,52.9972301731,609.6 -0.9412732567999998,52.995245861,609.6 -0.9363294217,52.99355912920001,609.6 -0.9311246926000001,52.9921878221,609.6 -0.9257141471,52.9911464456,609.6 -0.9201550256,52.9904460146,609.6 -0.9145061296,52.9900939372,609.6 -0.9088272037,52.9900939372,609.6 -0.9031783076999998,52.9904460146,609.6 -0.8976191863,52.9911464456,609.6 -0.8922086407000001,52.9921878221,609.6 -0.8870039117000001,52.99355912920001,609.6 -0.8820600765,52.995245861,609.6 -0.8774294700000002,52.9972301731,609.6 -0.873161132,52.9994910706,609.6 -0.8693002902,53.0020046282,609.6 -0.8658878807000001,53.00474424280001,609.6 -0.8629601145,53.0076809138,609.6 -0.8605480911,53.0107835481,609.6 -0.8586774672,53.014019289,609.6 -0.85736818,53.01735386240001,609.6 -0.8566342319,53.0207519397,609.6 -0.8564835367,53.0241775111,609.6 -0.85691783,53.0275942667,609.6 -0.8579326451,53.030965982,609.6 -0.8595173543,53.03425690120001,609.6 -0.8616552763999998,53.03743211769999,609.6 -0.8643238483,53.04045794449999,609.6 -0.8674948600999999,53.0433022727,609.6 -0.8711347507,53.0459349133,609.6 -0.8752049614999999,53.0483279189,609.6 -0.8796623439,53.0504558815,609.6 -0.8844596169000001,53.0522962039,609.6 -0.8895458695000001,53.0538293406,609.6 -0.8948671030999999,53.0550390067,609.6 -0.9003668070999999,53.055912352,609.6 -0.9059865625999999,53.0564400985,609.6 -0.9116666667,53.0566166392,609.6 + + + + +
+ + EGRU316B SYERSTON RWY 02L + 525833N 0005647W -
525847N 0005735W -
525949N 0005644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525933N 0005557W -
525833N 0005647W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9462611111,52.97575277779999,609.6 -0.9326351667,52.9925465278,609.6 -0.9371605542,52.99381488500001,609.6 -0.9414777553,52.9953246472,609.6 -0.9455515000000001,52.9970634722,609.6 -0.9596277778000001,52.9797083333,609.6 -0.9462611111,52.97575277779999,609.6 + + + + +
+ + EGRU316C SYERSTON RWY 20R + 530411N 0005312W -
530356N 0005223W -
530308N 0005303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530320N 0005353W -
530411N 0005312W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8865611111,53.06962499999999,609.6 -0.8979961667000002,53.0555806111,609.6 -0.8932158648,53.0547037456,609.6 -0.8885868653,53.0535700163,609.6 -0.8841471111,53.0521887222,609.6 -0.8731666667,53.0656694444,609.6 -0.8865611111,53.06962499999999,609.6 + + + + +
+ + EGRU316D SYERSTON RWY 02R + 525834N 0005641W -
525848N 0005729W -
525948N 0005640W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525932N 0005553W -
525834N 0005641W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9445833333,52.9761,609.6 -0.9314683889000001,52.99226672219999,609.6 -0.9360344625999999,52.9934709154,609.6 -0.9404020882,52.9949186579,609.6 -0.9445356667000001,52.9965981667,609.6 -0.9579527778,52.9800527778,609.6 -0.9445833333,52.9761,609.6 + + + + +
+ + EGRU316E SYERSTON RWY 20L + 530411N 0005306W -
530357N 0005218W -
530307N 0005259W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530319N 0005348W -
530411N 0005306W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8850333333,53.0698027778,609.6 -0.8967719444,53.0553830278,609.6 -0.8920324996,53.0544416819,609.6 -0.8874536336000001,53.05324629319999,609.6 -0.8830727778,53.0518066389,609.6 -0.8716361110999999,53.06584999999999,609.6 -0.8850333333,53.0698027778,609.6 + + + + +
+ + EGRU316F SYERSTON RWY 06 + 525941N 0005911W -
530010N 0005936W -
530043N 0005749W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530015N 0005724W -
525941N 0005911W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9864583333,52.99472777779999,609.6 -0.9567000000000001,53.0040936667,609.6 -0.9593936936,53.0066201301,609.6 -0.9616990915,53.0092827496,609.6 -0.9635973611,53.0120598611,609.6 -0.9933361111,53.0027,609.6 -0.9864583333,52.99472777779999,609.6 + + + + +
+ + EGRU316G SYERSTON RWY 24 + 530305N 0005018W -
530236N 0004953W -
530204N 0005135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530233N 0005200W -
530305N 0005018W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8383527777999999,53.0513527778,609.6 -0.8665545278,53.0425228056,609.6 -0.8638693661999999,53.0399925578,609.6 -0.8615739082,53.03732666330001,609.6 -0.8596867778,53.0345468611,609.6 -0.8314638889,53.0433833333,609.6 -0.8383527777999999,53.0513527778,609.6 + + + + +
+ + EGRU316H SYERSTON RWY 06L + 525945N 0005907W -
530013N 0005931W -
530045N 0005750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530016N 0005726W -
525945N 0005907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9851694444,52.99570000000001,609.6 -0.9571801944,53.0045089444,609.6 -0.959810169,53.00706010329999,609.6 -0.9620483698,53.00974386450001,609.6 -0.9638765,53.0125383889,609.6 -0.9920472222,53.0036722222,609.6 -0.9851694444,52.99570000000001,609.6 + + + + +
+ + EGRU316I SYERSTON RWY 24R + 530301N 0005038W -
530232N 0005013W -
530206N 0005136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530235N 0005201W -
530301N 0005038W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8438194444,53.0502083333,609.6 -0.8670451944000002,53.0429354444,609.6 -0.8642959963000001,53.0404299106,609.6 -0.8619331102,53.0377851374,609.6 -0.8599757221999998,53.0350226944,609.6 -0.8369305556,53.0422388889,609.6 -0.8438194444,53.0502083333,609.6 + + + + +
+ + EGRU316J SYERSTON RWY 06R + 525942N 0005904W -
530010N 0005929W -
530042N 0005748W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530014N 0005723W -
525942N 0005904W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9844611111,52.9948861111,609.6 -0.9562944167,53.0037530833,609.6 -0.9590402789,53.0062585353,609.6 -0.961400833,53.00890304819999,609.6 -0.9633568056,53.0116651111,609.6 -0.9913388889,53.0028555556,609.6 -0.9844611111,52.9948861111,609.6 + + + + +
+ + EGRU316K SYERSTON RWY 24L + 530256N 0005042W -
530227N 0005017W -
530203N 0005134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530232N 0005158W -
530256N 0005042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8450555555999999,53.0487972222,609.6 -0.8661643610999999,53.0421849444,609.6 -0.8635312747,53.03963472920001,609.6 -0.8612906516,53.0369517821,609.6 -0.8594606943999998,53.03415797219999,609.6 -0.8381666667,53.0408277778,609.6 -0.8450555555999999,53.0487972222,609.6 + + + + +
+ + EGRU316L SYERSTON RWY 11 + 530158N 0005936W -
530229N 0005919W -
530210N 0005745W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530139N 0005759W -
530158N 0005936W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9932277778,53.0327916667,609.6 -0.9664401111000001,53.0274773611,609.6 -0.9655974503999999,53.0304427487,609.6 -0.9643139209,53.0333501353,609.6 -0.9625999167,53.03617575,609.6 -0.9885555556,53.041325,609.6 -0.9932277778,53.0327916667,609.6 + + + + +
+ + EGRU316M SYERSTON RWY 29 + 530042N 0005021W -
530011N 0005038W -
530025N 0005149W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530055N 0005129W -
530042N 0005021W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8391277778,53.01158611109999,609.6 -0.8580746667,53.0153695556,609.6 -0.8594877637,53.0124841721,609.6 -0.8613268855,53.0096875054,609.6 -0.8635769444,53.0070023889,609.6 -0.8437972222,53.0030527778,609.6 -0.8391277778,53.01158611109999,609.6 + + + + +
+ + EGRU316N SYERSTON RWY 11L + 530201N 0005937W -
530231N 0005921W -
530212N 0005744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530141N 0005759W -
530201N 0005937W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9937388889,53.0334777778,609.6 -0.9663150833000002,53.0280407778,609.6 -0.965389513,53.0309945302,609.6 -0.9640255096,53.0338858783,609.6 -0.9622341110999999,53.0366912222,609.6 -0.9890666666999999,53.04201111110001,609.6 -0.9937388889,53.0334777778,609.6 + + + + +
+ + EGRU316O SYERSTON RWY 29R + 530038N 0004954W -
530008N 0005010W -
530027N 0005147W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530057N 0005128W -
530038N 0004954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8315305556,53.0106722222,609.6 -0.8578550556,53.01592669439999,609.6 -0.8591842718,53.0130296541,609.6 -0.8609412356999999,53.0102167252,609.6 -0.8631115556,53.00751083330001,609.6 -0.8361972222,53.00213888889999,609.6 -0.8315305556,53.0106722222,609.6 + + + + +
+ + EGRU316P SYERSTON RWY 11R + 530157N 0005940W -
530228N 0005923W -
530209N 0005747W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530137N 0005800W -
530157N 0005940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9944416667,53.03249722220001,609.6 -0.9665396667,53.0269653611,609.6 -0.9657723513000001,53.029941211,609.6 -0.9645618371,53.0328630501,609.6 -0.9629179722,53.0357069444,609.6 -0.9897694444,53.0410305556,609.6 -0.9944416667,53.03249722220001,609.6 + + + + +
+ + EGRU316Q SYERSTON RWY 29L + 530034N 0004949W -
530003N 0005006W -
530024N 0005150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530054N 0005130W -
530034N 0004949W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8303138889,53.00930833330001,609.6 -0.8582771389,53.01489019440001,609.6 -0.8597627878,53.0120150787,609.6 -0.8616730086,53.0092326862,609.6 -0.8639921111,53.0065657778,609.6 -0.8349805556,53.000775,609.6 -0.8303138889,53.00930833330001,609.6 + + + + +
+ + EGRU316R SYERSTON RWY 15 + 530357N 0005715W -
530413N 0005628W -
530319N 0005538W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530306N 0005627W -
530357N 0005715W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9541083332999999,53.0658666667,609.6 -0.9407998056,53.05160730560001,609.6 -0.9364328997,53.0530812795,609.6 -0.9318622098,53.05431083599999,609.6 -0.9271253333,53.0552858611,609.6 -0.9411000000000002,53.0702638889,609.6 -0.9541083332999999,53.0658666667,609.6 + + + + +
+ + EGRU316S SYERSTON RWY 33 + 525859N 0005135W -
525843N 0005222W -
525937N 0005312W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525955N 0005228W -
525859N 0005135W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8598138889,52.9829722222,609.6 -0.8744734444,52.9987451111,609.6 -0.8783162842,52.99681589679999,609.6 -0.8824324816,52.995104339,609.6 -0.8867882778,52.9936244722,609.6 -0.8727944444,52.9785722222,609.6 -0.8598138889,52.9829722222,609.6 + + + + +
+ + EGRU316T SYERSTON RWY 15L + 530354N 0005709W -
530410N 0005622W -
530320N 0005534W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530307N 0005624W -
530354N 0005709W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9523777778,53.06511111109999,609.6 -0.9400369167,53.0518878056,609.6 -0.935623392,53.0533211891,609.6 -0.9310120734,53.05450734839999,609.6 -0.9262410277999999,53.0554365,609.6 -0.9393694444,53.0695083333,609.6 -0.9523777778,53.06511111109999,609.6 + + + + +
+ + EGRU316U SYERSTON RWY 33R + 525857N 0005130W -
525841N 0005217W -
525938N 0005310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525957N 0005226W -
525857N 0005130W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8583611111,52.9825083333,609.6 -0.8738008056,52.9991213611,609.6 -0.8775965703,52.99715075990001,609.6 -0.8816725552999999,52.99539580370001,609.6 -0.8859951944,52.99387091669999,609.6 -0.8713416667000001,52.9781083333,609.6 -0.8583611111,52.9825083333,609.6 + + + + +
+ + EGRU316V SYERSTON RWY 15R + 530355N 0005717W -
530411N 0005630W -
530318N 0005541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530305N 0005630W -
530355N 0005717W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9546638889,53.0653361111,609.6 -0.94156925,53.0513138889,609.6 -0.9372483332,53.0528294872,609.6 -0.9327174011,53.0541032867,609.6 -0.9280136389,53.0551248333,609.6 -0.9416555556,53.0697388889,609.6 -0.9546638889,53.0653361111,609.6 + + + + +
+ + EGRU316W SYERSTON RWY 33L + 525901N 0005141W -
525845N 0005228W -
525936N 0005315W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525954N 0005231W -
525901N 0005141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8614138889,52.9836138889,609.6 -0.8751460277999998,52.9983811389,609.6 -0.8790351997000001,52.9964925478,609.6 -0.8831911022,52.9948236641,609.6 -0.88757975,52.99338813890001,609.6 -0.8743916667000001,52.97921111109999,609.6 -0.8614138889,52.9836138889,609.6 + + + + +
+ + EGRU317A SANDTOFT + A circle, 2 NM radius, centred at 533335N 0005130W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8583333332999999,53.5930025171,609.6 -0.8640851205,53.5928259897,609.6 -0.8697757947,53.5922982831,609.6 -0.8753448971,53.5914250039,609.6 -0.880733269,53.5902154301,609.6 -0.8858836849,53.58868241129999,609.6 -0.8907414632999999,53.58684223189999,609.6 -0.8952550498,53.5847144365,609.6 -0.8993765668,53.5823216214,609.6 -0.9030623216,53.5796891934,609.6 -0.9062732702000001,53.57684509849999,609.6 -0.9089754301000001,53.5738195239,609.6 -0.9111402375999998,53.5706445766,609.6 -0.9127448481,53.5673539412,609.6 -0.913772373,53.5639825219,609.6 -0.9142120543999999,53.5605660714,609.6 -0.9140593726999999,53.5571408114,609.6 -0.9133160892,53.5537430482,609.6 -0.9119902209,53.5504087882,609.6 -0.91009595,53.5471733563,609.6 -0.907653468,53.5440710226,609.6 -0.9046887571,53.5411346403,609.6 -0.9012333109,53.5383952985,609.6 -0.8973237974000001,53.5358819942,609.6 -0.8930016694,53.53362132709999,609.6 -0.8883127239,53.531637219,609.6 -0.8833066178,53.5299506621,609.6 -0.8780363436000002,53.5285794981,609.6 -0.8725576704000001,53.52753823089999,609.6 -0.8669285573,53.5268378737,609.6 -0.8612085435,53.5264858335,609.6 -0.8554581230999999,53.5264858335,609.6 -0.8497381094000001,53.5268378737,609.6 -0.8441089963,53.52753823089999,609.6 -0.8386303231,53.5285794981,609.6 -0.8333600489,53.5299506621,609.6 -0.8283539428,53.531637219,609.6 -0.8236649971999999,53.53362132709999,609.6 -0.8193428692,53.5358819942,609.6 -0.8154333557999999,53.5383952985,609.6 -0.8119779095,53.5411346403,609.6 -0.8090131986999999,53.5440710226,609.6 -0.8065707167,53.5471733563,609.6 -0.8046764457999999,53.5504087882,609.6 -0.8033505775000001,53.5537430482,609.6 -0.802607294,53.5571408114,609.6 -0.8024546123,53.5605660714,609.6 -0.8028942936,53.5639825219,609.6 -0.8039218185999999,53.5673539412,609.6 -0.805526429,53.5706445766,609.6 -0.8076912366,53.5738195239,609.6 -0.8103933964,53.57684509849999,609.6 -0.8136043451,53.5796891934,609.6 -0.8172900999,53.5823216214,609.6 -0.8214116167999999,53.5847144365,609.6 -0.8259252034,53.58684223189999,609.6 -0.8307829817000001,53.58868241129999,609.6 -0.8359333976,53.5902154301,609.6 -0.8413217696,53.5914250039,609.6 -0.8468908719000001,53.5922982831,609.6 -0.8525815462,53.5928259897,609.6 -0.8583333332999999,53.5930025171,609.6 + + + + +
+ + EGRU317B SANDTOFT RWY 05 + 533118N 0005438W -
533141N 0005517W -
533222N 0005409W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to
533159N 0005330W -
533118N 0005438W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.91055,53.5216333333,609.6 -0.8917588611,53.5330525556,609.6 -0.8956587241,53.5349549572,609.6 -0.8992552579999998,53.537058912,609.6 -0.9025191667,53.5393473333,609.6 -0.9213083332999998,53.5279277778,609.6 -0.91055,53.5216333333,609.6 + + + + +
+ + EGRU317C SANDTOFT RWY 23 + 533547N 0004830W -
533525N 0004751W -
533448N 0004851W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to
533511N 0004930W -
533547N 0004830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8082888888999999,53.5964805556,609.6 -0.8249266389,53.5864094444,609.6 -0.8210211529000001,53.58450809960001,609.6 -0.8174199323999999,53.5824049166,609.6 -0.8141522778,53.5801170556,609.6 -0.7975111110999999,53.5901888889,609.6 -0.8082888888999999,53.5964805556,609.6 + + + + +
+ + EGRU319A WADDINGTON + A circle, 2.5 NM radius, centred at 530958N 0003126W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5238888889,53.2077142103,609.6 -0.5302827139,53.207536568,609.6 -0.5366218315,53.207005161,609.6 -0.5428520067,53.2061245359,609.6 -0.5489199443,53.204902227,609.6 -0.5547737485999999,53.2033486911,609.6 -0.5603633708,53.20147721719999,609.6 -0.5656410391,53.19930381209999,609.6 -0.5705616695,53.1968470626,609.6 -0.5750832522,53.194127975,609.6 -0.5791672108,53.19116979489999,609.6 -0.582778732,53.1879978065,609.6 -0.5858870608,53.1846391161,609.6 -0.5884657617,53.1811224189,609.6 -0.5904929406,53.1774777527,609.6 -0.5919514285,53.1737362408,609.6 -0.5928289237,53.1699298254,609.6 -0.5931180914,53.16609099429999,609.6 -0.5928166217,53.1622525033,609.6 -0.5919272434,53.1584470964,609.6 -0.5904576959,53.15470722720001,609.6 -0.5884206578,53.1510647819,609.6 -0.5858336336,53.14755080820001,609.6 -0.5827188008,53.1441952511,609.6 -0.5791028166,53.1410266992,609.6 -0.5750165877,53.1380721416,609.6 -0.5704950051,53.13535673929999,609.6 -0.5655766448,53.1329036124,609.6 -0.5603034396,53.1307336437,609.6 -0.5547203213,53.12886530310001,609.6 -0.5488748403,53.12731449070001,609.6 -0.542816762,53.1260944027,609.6 -0.5365976464,53.1252154203,609.6 -0.5302704118,53.1246850218,609.6 -0.5238888889,53.12450771950001,609.6 -0.517507366,53.1246850218,609.6 -0.5111801314,53.1252154203,609.6 -0.5049610157,53.1260944027,609.6 -0.4989029375,53.12731449070001,609.6 -0.4930574565,53.12886530310001,609.6 -0.4874743382000001,53.1307336437,609.6 -0.4822011329,53.1329036124,609.6 -0.4772827727,53.13535673929999,609.6 -0.4727611901,53.1380721416,609.6 -0.4686749612,53.1410266992,609.6 -0.465058977,53.1441952511,609.6 -0.4619441442,53.14755080820001,609.6 -0.4593571200000001,53.1510647819,609.6 -0.4573200818,53.15470722720001,609.6 -0.4558505344000001,53.1584470964,609.6 -0.4549611561,53.1622525033,609.6 -0.4546596863,53.16609099429999,609.6 -0.4549488541,53.1699298254,609.6 -0.4558263492,53.1737362408,609.6 -0.4572848372,53.1774777527,609.6 -0.4593120161,53.1811224189,609.6 -0.4618907169000001,53.1846391161,609.6 -0.4649990458000001,53.1879978065,609.6 -0.4686105669999999,53.19116979489999,609.6 -0.4726945256000001,53.194127975,609.6 -0.4772161083000001,53.1968470626,609.6 -0.4821367386,53.19930381209999,609.6 -0.487414407,53.20147721719999,609.6 -0.4930040291,53.2033486911,609.6 -0.4988578335000001,53.204902227,609.6 -0.504925771,53.2061245359,609.6 -0.5111559462,53.207005161,609.6 -0.5174950639,53.207536568,609.6 -0.5238888889,53.2077142103,609.6 + + + + +
+ + EGRU319B WADDINGTON RWY 02 + 530639N 0003308W -
530651N 0003358W -
530746N 0003322W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to
530734N 0003233W -
530639N 0003308W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5523125556,53.11095211109999,609.6 -0.54236325,53.12601786110001,609.6 -0.5471194495,53.1269222092,609.6 -0.5517551548,53.1280302058,609.6 -0.5562463056,53.1293361111,609.6 -0.5661892777999999,53.1142725833,609.6 -0.5523125556,53.11095211109999,609.6 + + + + +
+ + EGRU319C WADDINGTON RWY 20 + 531313N 0002946W -
531301N 0002856W -
531210N 0002929W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to
531222N 0003019W -
531313N 0002946W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4960258889,53.2203266667,609.6 -0.5053914167,53.2062031111,609.6 -0.5006270692,53.2052975907,609.6 -0.4959840364000001,53.2041880917,609.6 -0.4914865278,53.2028803889,609.6 -0.4821149167,53.21700625,609.6 -0.4960258889,53.2203266667,609.6 + + + + +
+ + EGRU320A CRANWELL + A circle, 2.5 NM radius, centred at 530147N 0002934W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4927527778,53.07133739139999,609.6 -0.4991263854,53.0711597458,609.6 -0.5054454595,53.070628329,609.6 -0.5116559371,53.06974768780001,609.6 -0.5177046922,53.0685253563,609.6 -0.523539994,53.06697179129999,609.6 -0.5291119522,53.0651002821,609.6 -0.5343729466,53.06292683549999,609.6 -0.5392780356,53.0604700383,609.6 -0.5437853424,53.0577508973,609.6 -0.5478564126,53.05479265799999,609.6 -0.5514565422,53.0516206051,609.6 -0.5545550733,53.0482618451,609.6 -0.5571256530000001,53.04474507350001,609.6 -0.5591464559,53.0411003288,609.6 -0.5606003663,53.0373587348,609.6 -0.5614751202,53.03355223420001,609.6 -0.5617634053,53.0297133154,609.6 -0.5614629176,53.025874735,609.6 -0.5605763766,53.0220692379,609.6 -0.559111496,53.0183292784,609.6 -0.5570809135,53.0146867436,609.6 -0.5545020777,53.011172682,609.6 -0.5513970952,53.0078170398,609.6 -0.5477925386,53.0046484063,609.6 -0.5437192166,53.00169377149999,609.6 -0.5392119097,52.9989782975,609.6 -0.5343090725,52.99652510500001,609.6 -0.5290525052,52.9943550778,609.6 -0.5234869983,52.9924866863,609.6 -0.5176599526,52.9909358313,609.6 -0.5116209771,52.98971570970001,609.6 -0.5054214697,52.988836703,609.6 -0.4991141827,52.98830628979999,609.6 -0.4927527778,52.9881289825,609.6 -0.4863913728,52.98830628979999,609.6 -0.4800840859,52.988836703,609.6 -0.4738845785,52.98971570970001,609.6 -0.467845603,52.9909358313,609.6 -0.4620185572,52.9924866863,609.6 -0.4564530503999999,52.9943550778,609.6 -0.4511964831,52.99652510500001,609.6 -0.4462936458,52.9989782975,609.6 -0.441786339,53.00169377149999,609.6 -0.437713017,53.0046484063,609.6 -0.4341084603,53.0078170398,609.6 -0.4310034778,53.011172682,609.6 -0.428424642,53.0146867436,609.6 -0.4263940595,53.0183292784,609.6 -0.424929179,53.0220692379,609.6 -0.424042638,53.025874735,609.6 -0.4237421503,53.0297133154,609.6 -0.4240304353,53.03355223420001,609.6 -0.4249051893,53.0373587348,609.6 -0.4263590997,53.0411003288,609.6 -0.4283799025,53.04474507350001,609.6 -0.4309504822,53.0482618451,609.6 -0.4340490133,53.0516206051,609.6 -0.437649143,53.05479265799999,609.6 -0.4417202131,53.0577508973,609.6 -0.4462275199,53.0604700383,609.6 -0.451132609,53.06292683549999,609.6 -0.4563936033,53.0651002821,609.6 -0.4619655615,53.06697179129999,609.6 -0.4678008634,53.0685253563,609.6 -0.4738496185,53.06974768780001,609.6 -0.4800600961,53.070628329,609.6 -0.4863791702,53.0711597458,609.6 -0.4927527778,53.07133739139999,609.6 + + + + +
+ + EGRU320B CRANWELL RWY 01 + 525833N 0002919W -
525838N 0003012W -
525918N 0003003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
525918N 0002909W -
525833N 0002919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4886638889,52.9759416667,609.6 -0.4857053333,52.9883466944,609.6 -0.4907135656,52.9881471692,609.6 -0.4957325729,52.9881678233,609.6 -0.5007358333,52.9884085556,609.6 -0.5034,52.97722222220001,609.6 -0.4886638889,52.9759416667,609.6 + + + + +
+ + EGRU320C CRANWELL RWY 19 + 530445N 0002845W -
530440N 0002751W -
530406N 0002800W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530415N 0002852W -
530445N 0002845W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4790694444,53.0791638889,609.6 -0.4810846389,53.0707389722,609.6 -0.4761629955,53.0701185314,609.6 -0.4713295119,53.0692838807,609.6 -0.4666098611,53.0682394722,609.6 -0.4643,53.0778833333,609.6 -0.4790694444,53.0791638889,609.6 + + + + +
+ + EGRU320D CRANWELL RWY 08 + 530107N 0003443W -
530139N 0003450W -
530144N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530112N 0003335W -
530107N 0003443W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5786777778,53.01853333330001,609.6 -0.559841,53.02000063890001,609.6 -0.5608322153999999,53.0229411873,609.6 -0.5614694696,53.0259171598,609.6 -0.5617493611,53.0289130833,609.6 -0.5805666667,53.0274472222,609.6 -0.5786777778,53.01853333330001,609.6 + + + + +
+ + EGRU320E CRANWELL RWY 26 + 530227N 0002421W -
530155N 0002414W -
530150N 0002526W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530222N 0002532W -
530227N 0002421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4057472221999999,53.0409472222,609.6 -0.4256331389,53.0394249444,609.6 -0.4246510811999999,53.0364830877,609.6 -0.4240234783999999,53.0335062108,609.6 -0.4237535278,53.03050980559999,609.6 -0.40385,53.0320333333,609.6 -0.4057472221999999,53.0409472222,609.6 + + + + +
+ + EGRU320F CRANWELL RWY 08N + 530107N 0003416W -
530139N 0003423W -
530142N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530110N 0003335W -
530107N 0003416W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5711777778,53.01854999999999,609.6 -0.55959675,53.01940886109999,609.6 -0.560659422,53.022340648,609.6 -0.5613689532,53.02531099199999,609.6 -0.5617215833,53.02830444439999,609.6 -0.5729805556000001,53.0274694444,609.6 -0.5711777778,53.01854999999999,609.6 + + + + +
+ + EGRU320G CRANWELL RWY 26N + 530221N 0002450W -
530149N 0002443W -
530146N 0002525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530218N 0002531W -
530221N 0002450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4137722222,53.039175,609.6 -0.4252282222,53.0383400278,609.6 -0.4243769460999999,53.0353831851,609.6 -0.4238815851,53.0323970413,609.6 -0.4237446389000001,53.02939713889999,609.6 -0.4119666666999999,53.0302555556,609.6 -0.4137722222,53.039175,609.6 + + + + +
+ + EGRU320H CRANWELL RWY 06 + 530100N 0003352W -
530129N 0003415W -
530139N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530106N 0003333W -
530100N 0003352W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5643539444,53.0167546667,609.6 -0.5590889999999999,53.0182818889,609.6 -0.56032936,53.0213150389,609.6 -0.5611889152,53.0243957527,609.6 -0.56166275,53.02750666670001,609.6 -0.5708006667,53.0248561111,609.6 -0.5643539444,53.0167546667,609.6 + + + + +
+ + EGRU320I CRANWELL RWY 24 + 530406N 0002513W -
530337N 0002450W -
530314N 0002611W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530339N 0002648W -
530406N 0002513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4202738333,53.0683875833,609.6 -0.4467458333,53.0607521667,609.6 -0.4430133857,53.0585835142,609.6 -0.439561951,53.05625214110001,609.6 -0.4364109722,53.0537712222,609.6 -0.4138206111,53.0602862222,609.6 -0.4202738333,53.0683875833,609.6 + + + + +
+ + EGRU320K CRANWELL RWY 21 + 530519N 0002721W -
530503N 0002635W -
530359N 0002737W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530411N 0002828W -
530519N 0002721W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4558644444,53.08874525,609.6 -0.4743584167,53.0698336944,609.6 -0.4695525918,53.0689181653,609.6 -0.4648706423,53.0677938034,609.6 -0.4603375555999999,53.06646661109999,609.6 -0.4430011389,53.0841885,609.6 -0.4558644444,53.08874525,609.6 + + + + +
+ + EGRU321A HUMBERSIDE + A circle, 2.5 NM radius, centred at 533424N 0002105W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3514583333,53.61503079920001,609.6 -0.3579135341,53.6148531665,609.6 -0.3643135,53.6143217883,609.6 -0.370603473,53.61344121129999,609.6 -0.3767296443,53.61221896959999,609.6 -0.3826396183,53.6106655197,609.6 -0.3882828644,53.6087941506,609.6 -0.3936111511,53.60662086890001,609.6 -0.3985789612,53.6041642607,609.6 -0.4031438816999999,53.601445332,609.6 -0.4072669666,53.5984873276,609.6 -0.4109130692,53.5953155311,609.6 -0.4140511412,53.5919570477,609.6 -0.4166544952,53.5884405714,609.6 -0.4187010295,53.58479613869999,609.6 -0.4201734131,53.58105487139999,609.6 -0.4210592292,53.5772487098,609.6 -0.4213510757,53.5734101397,609.6 -0.4210466237,53.5695719148,609.6 -0.4201486315,53.5657667769,609.6 -0.4186649156,53.56202717690001,609.6 -0.4166082789,53.5583849984,609.6 -0.4139963963,53.5548712864,609.6 -0.41085166,53.5515159834,609.6 -0.4072009842000001,53.54834767490001,609.6 -0.4030755731,53.54539334739999,609.6 -0.3985106526,53.5426781594,609.6 -0.3935451687,53.5402252281,609.6 -0.388221455,53.5380554343,609.6 -0.3825848733000001,53.5361872456,609.6 -0.3766834279,53.5346365601,609.6 -0.3705673591,53.5334165726,609.6 -0.3642887183,53.5325376629,609.6 -0.3579009286,53.5320073084,609.6 -0.3514583333,53.5318300209,609.6 -0.3450157381,53.5320073084,609.6 -0.3386279483,53.5325376629,609.6 -0.3323493076,53.5334165726,609.6 -0.3262332388,53.5346365601,609.6 -0.3203317933,53.5361872456,609.6 -0.3146952116,53.5380554343,609.6 -0.309371498,53.5402252281,609.6 -0.304406014,53.5426781594,609.6 -0.2998410935,53.54539334739999,609.6 -0.2957156825,53.54834767490001,609.6 -0.2920650067,53.5515159834,609.6 -0.2889202703,53.5548712864,609.6 -0.2863083878,53.5583849984,609.6 -0.284251751,53.56202717690001,609.6 -0.2827680351,53.5657667769,609.6 -0.2818700429,53.5695719148,609.6 -0.281565591,53.5734101397,609.6 -0.2818574375,53.5772487098,609.6 -0.2827432535,53.58105487139999,609.6 -0.2842156372,53.58479613869999,609.6 -0.2862621715,53.5884405714,609.6 -0.2888655254,53.5919570477,609.6 -0.2920035974,53.5953155311,609.6 -0.2956497001,53.5984873276,609.6 -0.299772785,53.601445332,609.6 -0.3043377054,53.6041642607,609.6 -0.3093055156,53.60662086890001,609.6 -0.3146338023,53.6087941506,609.6 -0.3202770483,53.6106655197,609.6 -0.3261870224,53.61221896959999,609.6 -0.3323131937,53.61344121129999,609.6 -0.3386031667,53.6143217883,609.6 -0.3450031326,53.6148531665,609.6 -0.3514583333,53.61503079920001,609.6 + + + + +
+ + EGRU321B HUMBERSIDE RWY 02 + 533119N 0002244W -
533132N 0002334W -
533213N 0002305W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533201N 0002215W -
533119N 0002244W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3787722222000001,53.5220722222,609.6 -0.3709044722,53.5334741944,609.6 -0.3756882022,53.5344122774,609.6 -0.380346243,53.53555314679999,609.6 -0.3848544167,53.5368908889,609.6 -0.3927166667,53.5254916667,609.6 -0.3787722222000001,53.5220722222,609.6 + + + + +
+ + EGRU321C HUMBERSIDE RWY 20 + 533729N 0001927W -
533717N 0001836W -
533636N 0001905W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533648N 0001955W -
533729N 0001927W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3240805556,53.6247805556,609.6 -0.33197675,53.6133836944,609.6 -0.3271853186,53.6124439859,609.6 -0.32252048,53.6113011963,609.6 -0.3180065556,53.6099612778,609.6 -0.3101027778,53.62136388889999,609.6 -0.3240805556,53.6247805556,609.6 + + + + +
+ + EGRU321D HUMBERSIDE RWY 08 + 533356N 0002538W -
533428N 0002545W -
533430N 0002517W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533358N 0002513W -
533356N 0002538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4272916667,53.5654611111,609.6 -0.4202290833,53.5660261111,609.6 -0.420950153,53.5690011489,609.6 -0.4213085477,53.5719994114,609.6 -0.4213023055999999,53.57500525,609.6 -0.4292833333,53.57436666669999,609.6 -0.4272916667,53.5654611111,609.6 + + + + +
+ + EGRU321E HUMBERSIDE RWY 26 + 533513N 0001609W -
533441N 0001602W -
533437N 0001655W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533509N 0001705W -
533513N 0001609W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2691388889,53.587075,609.6 -0.2847413611,53.5858466111,609.6 -0.2834108694,53.5829460348,609.6 -0.2824360879,53.5799958388,609.6 -0.2818220278,53.5770114444,609.6 -0.2671444444,53.5781666667,609.6 -0.2691388889,53.587075,609.6 + + + + +
+ + EGRU322A WICKENBY + A circle, 2 NM radius, centred at 531901N 0002056W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3487972222,53.3502177668,609.6 -0.3545162778,53.3500412334,609.6 -0.3601745694,53.3495135088,609.6 -0.3657119835,53.34864019969999,609.6 -0.371069699,53.3474305843,609.6 -0.376190817,53.34589751230001,609.6 -0.3810209678,53.3440572683,609.6 -0.3855088907999999,53.34192939739999,609.6 -0.3896069807,53.3395364964,609.6 -0.3932717934,53.3369039724,609.6 -0.3964645064000001,53.3340597721,609.6 -0.3991513297,53.3310340837,609.6 -0.4013038611,53.3278590148,609.6 -0.4028993846,53.3245682512,609.6 -0.4039211062,53.3211966981,609.6 -0.4043583274999999,53.3177801097,609.6 -0.4042065530999999,53.314354709,609.6 -0.4034675323999999,53.3109568038,609.6 -0.4021492354,53.3076224021,609.6 -0.4002657622,53.30438683049999,609.6 -0.3978371881,53.3012843609,609.6 -0.3948893466999999,53.2983478481,609.6 -0.3914535517,53.29560838279999,609.6 -0.3875662623,53.293094964,609.6 -0.3832686955,53.2908341927,609.6 -0.3786063882,53.2888499923,609.6 -0.3736287158,53.2871633562,609.6 -0.3683883700999999,53.2857921275,609.6 -0.3629408047,53.2847508108,609.6 -0.3573436505,53.2840504202,609.6 -0.3516561099,53.2836983632,609.6 -0.3459383346,53.2836983632,609.6 -0.3402507939,53.2840504202,609.6 -0.3346536397,53.2847508108,609.6 -0.3292060743,53.2857921275,609.6 -0.3239657287,53.2871633562,609.6 -0.3189880562,53.2888499923,609.6 -0.3143257489,53.2908341927,609.6 -0.3100281821,53.293094964,609.6 -0.3061408928,53.29560838279999,609.6 -0.3027050977,53.2983478481,609.6 -0.2997572563,53.3012843609,609.6 -0.2973286823,53.30438683049999,609.6 -0.295445209,53.3076224021,609.6 -0.294126912,53.3109568038,609.6 -0.2933878914,53.314354709,609.6 -0.2932361169,53.3177801097,609.6 -0.2936733382,53.3211966981,609.6 -0.2946950599,53.3245682512,609.6 -0.2962905833,53.3278590148,609.6 -0.2984431148,53.3310340837,609.6 -0.301129938,53.3340597721,609.6 -0.3043226511,53.3369039724,609.6 -0.3079874638,53.3395364964,609.6 -0.3120855537,53.34192939739999,609.6 -0.3165734767,53.3440572683,609.6 -0.3214036274,53.34589751230001,609.6 -0.3265247454,53.3474305843,609.6 -0.331882461,53.34864019969999,609.6 -0.337419875,53.3495135088,609.6 -0.3430781667,53.3500412334,609.6 -0.3487972222,53.3502177668,609.6 + + + + +
+ + EGRU322B WICKENBY RWY 03 + 531620N 0002232W -
531634N 0002321W -
531720N 0002245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
531707N 0002156W -
531620N 0002232W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3756833332999999,53.27223333329999,609.6 -0.3654925278000001,53.2851925278,609.6 -0.3702002326000001,53.2862230041,609.6 -0.374734012,53.2875034333,609.6 -0.3790569999999999,53.2890234167,609.6 -0.3892416667,53.2760666667,609.6 -0.3756833332999999,53.27223333329999,609.6 + + + + +
+ + EGRU322C WICKENBY RWY 21 + 532142N 0001919W -
532128N 0001830W -
532041N 0001907W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
532055N 0001955W -
532142N 0001919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3218611111,53.36162499999999,609.6 -0.3320773056,53.3486772222,609.6 -0.32736351,53.3476452269,609.6 -0.3228246477,53.34636297319999,609.6 -0.31849775,53.3448409167,609.6 -0.308275,53.35779166670001,609.6 -0.3218611111,53.36162499999999,609.6 + + + + +
+ + EGRU322D WICKENBY RWY 15 + 532121N 0002345W -
532137N 0002258W -
532051N 0002214W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
532035N 0002300W -
532121N 0002345W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3958777778,53.3559444444,609.6 -0.3834495556,53.3429619167,609.6 -0.3793878275,53.34472682669999,609.6 -0.3750764222,53.34626523630001,609.6 -0.3705505000000001,53.3475645833,609.6 -0.3828388889,53.3604055556,609.6 -0.3958777778,53.3559444444,609.6 + + + + +
+ + EGRU322E WICKENBY RWY 33 + 531643N 0001817W -
531627N 0001904W -
531709N 0001944W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
531725N 0001857W -
531643N 0001817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3046611111,53.2785583333,609.6 -0.3157443333,53.2901840278,609.6 -0.3199044072,53.28850849060001,609.6 -0.3242993329,53.2870643575,609.6 -0.3288933611,53.2858633611,609.6 -0.3176722222,53.2740972222,609.6 -0.3046611111,53.2785583333,609.6 + + + + +
+ + EGRU323A CONINGSBY + A circle, 2.5 NM radius, centred at 530535N 0000958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1661111111,53.1346591682,609.6 -0.1724940855,53.13448152419999,609.6 -0.1788224458,53.1339501119,609.6 -0.1850420493,53.1330694782,609.6 -0.1910996917,53.1318471572,609.6 -0.1969435658,53.1302936057,609.6 -0.2025237078,53.1284221129,609.6 -0.2077924272,53.1262486856,609.6 -0.2127047167,53.12379191059999,609.6 -0.2172186375,53.1210727944,609.6 -0.2212956789,53.1181145826,609.6 -0.2249010863,53.1149425597,609.6 -0.2280041568,53.11158383200001,609.6 -0.230578499,53.108067095,609.6 -0.2326022559,53.1044223867,609.6 -0.2340582872,53.1006808309,609.6 -0.2349343111,53.09687436990001,609.6 -0.2352230051,53.0930354918,609.6 -0.2349220625,53.0891969529,609.6 -0.234034207,53.08539149769999,609.6 -0.2325671642,53.0816515802,609.6 -0.2305335908,53.0780090869,609.6 -0.2279509613,53.0744950661,609.6 -0.2248414152,53.07113946340001,609.6 -0.2212315641,53.06797086779999,609.6 -0.2171522623,53.0650162689,609.6 -0.2126383414,53.0623008282,609.6 -0.2077283123,53.0598476661,609.6 -0.2024640366,53.0576776661,609.6 -0.1968903703,53.0558092983,609.6 -0.1910547834,53.054258463,609.6 -0.1850069576,53.053038357,609.6 -0.1787983656,53.0521593616,609.6 -0.1724818368,53.05162895519999,609.6 -0.1661111111,53.0514516503,609.6 -0.1597403854,53.05162895519999,609.6 -0.1534238567,53.0521593616,609.6 -0.1472152647,53.053038357,609.6 -0.1411674388,53.054258463,609.6 -0.1353318519,53.0558092983,609.6 -0.1297581856,53.0576776661,609.6 -0.1244939099,53.0598476661,609.6 -0.1195838808,53.0623008282,609.6 -0.1150699599,53.0650162689,609.6 -0.1109906581,53.06797086779999,609.6 -0.1073808071,53.07113946340001,609.6 -0.1042712609,53.0744950661,609.6 -0.1016886314,53.0780090869,609.6 -0.09965505799999999,53.0816515802,609.6 -0.0981880153,53.08539149769999,609.6 -0.0973001597,53.0891969529,609.6 -0.09699921709999999,53.0930354918,609.6 -0.09728791110000001,53.09687436990001,609.6 -0.09816393510000002,53.1006808309,609.6 -0.0996199663,53.1044223867,609.6 -0.1016437232,53.108067095,609.6 -0.1042180655,53.11158383200001,609.6 -0.1073211359,53.1149425597,609.6 -0.1109265433,53.1181145826,609.6 -0.1150035847,53.1210727944,609.6 -0.1195175056,53.12379191059999,609.6 -0.124429795,53.1262486856,609.6 -0.1296985144,53.1284221129,609.6 -0.1352786564,53.1302936057,609.6 -0.1411225305,53.1318471572,609.6 -0.1471801729,53.1330694782,609.6 -0.1533997764,53.1339501119,609.6 -0.1597281367,53.13448152419999,609.6 -0.1661111111,53.1346591682,609.6 + + + + +
+ + EGRU323B CONINGSBY RWY 07 + 530416N 0001515W -
530447N 0001532W -
530505N 0001402W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to
530434N 0001345W -
530416N 0001515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2541946667,53.0711036389,609.6 -0.2291673333,53.0760418333,609.6 -0.2310417153,53.0788218642,609.6 -0.2325787151,53.0816759933,609.6 -0.2337702778,53.0845893889,609.6 -0.2588251667,53.0796456944,609.6 -0.2541946667,53.0711036389,609.6 + + + + +
+ + EGRU323C CONINGSBY RWY 25 + 530655N 0000441W -
530624N 0000424W -
530606N 0000555W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to
530637N 0000611W -
530655N 0000441W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0779853056,53.1151844722,609.6 -0.1031692778,53.11025525,609.6 -0.1012750652,53.1074797611,609.6 -0.0997184131,53.104629315,609.6 -0.09850736110000001,53.10171875,609.6 -0.0733509722,53.1066424722,609.6 -0.0779853056,53.1151844722,609.6 + + + + +
+ + EGRU324A MONA + A circle, 2 NM radius, centred at 531533N 0042226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3740111111,53.29258197919999,609.6 -4.3797224662,53.2924054444,609.6 -4.3853731395,53.2918777155,609.6 -4.3909030984,53.2910043994,609.6 -4.3962536017,53.289794774,609.6 -4.4013678271,53.2882616893,609.6 -4.4061914781,53.28642143,609.6 -4.4106733634,53.2842935411,609.6 -4.4147659418,53.2819006196,609.6 -4.4184258276,53.2792680728,609.6 -4.4216142504,53.2764238474,609.6 -4.4242974655,53.2733981319,609.6 -4.4264471089,53.2702230341,609.6 -4.4280404944,53.2669322399,609.6 -4.4290608507,53.2635606551,609.6 -4.4294974932,53.26014403389999,609.6 -4.4293459322,53.25671859970001,609.6 -4.4286079143,53.2533206608,609.6 -4.4272913986,53.2499862254,609.6 -4.4254104656,53.2467506206,609.6 -4.4229851635,53.2436481187,609.6 -4.4200412909,53.2407115749,609.6 -4.416610119,53.2379720803,609.6 -4.4127280581,53.2354586342,609.6 -4.4084362697,53.2331978382,609.6 -4.4037802294,53.2312136158,609.6 -4.3988092463,53.229526961,609.6 -4.3935759418,53.2281557169,609.6 -4.388135695,53.2271143885,609.6 -4.3825460595,53.2264139899,609.6 -4.3768661586,53.226061929,609.6 -4.3711560636,53.226061929,609.6 -4.3654761627,53.2264139899,609.6 -4.3598865272,53.2271143885,609.6 -4.3544462804,53.2281557169,609.6 -4.3492129759,53.229526961,609.6 -4.3442419928,53.2312136158,609.6 -4.3395859526,53.2331978382,609.6 -4.3352941641,53.2354586342,609.6 -4.3314121032,53.2379720803,609.6 -4.3279809314,53.2407115749,609.6 -4.3250370587,53.2436481187,609.6 -4.3226117567,53.2467506206,609.6 -4.3207308237,53.2499862254,609.6 -4.3194143079,53.2533206608,609.6 -4.3186762901,53.25671859970001,609.6 -4.318524729,53.26014403389999,609.6 -4.3189613715,53.2635606551,609.6 -4.3199817278,53.2669322399,609.6 -4.3215751134,53.2702230341,609.6 -4.3237247567,53.2733981319,609.6 -4.3264079718,53.2764238474,609.6 -4.3295963947,53.2792680728,609.6 -4.3332562804,53.2819006196,609.6 -4.3373488588,53.2842935411,609.6 -4.3418307441,53.28642143,609.6 -4.3466543951,53.2882616893,609.6 -4.3517686205,53.289794774,609.6 -4.3571191238,53.2910043994,609.6 -4.3626490828,53.2918777155,609.6 -4.3682997561,53.2924054444,609.6 -4.3740111111,53.29258197919999,609.6 + + + + +
+ + EGRU324B MONA RWY 04 + 531255N 0042513W -
531315N 0042556W -
531409N 0042448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to
531349N 0042405W -
531255N 0042513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4203648889,53.2153488889,609.6 -4.40135675,53.2303406667,609.6 -4.4055967384,53.2319366862,609.6 -4.4095800249,53.23375540819999,609.6 -4.4132741944,53.2357820556,609.6 -4.4322736944,53.2207938056,609.6 -4.4203648889,53.2153488889,609.6 + + + + +
+ + EGRU324C MONA RWY 22 + 531813N 0041938W -
531753N 0041855W -
531658N 0042005W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to
531718N 0042048W -
531813N 0041938W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3271375,53.30356372220001,609.6 -4.34662625,53.2882521389,609.6 -4.3423830117,53.2866539207,609.6 -4.3383978058,53.2848328586,609.6 -4.3347031111,53.2828038056,609.6 -4.3152056667,53.2981188889,609.6 -4.3271375,53.30356372220001,609.6 + + + + +
+ + EGRU325 HMP ALTCOURSE + 532802N 0025617W -
532801N 0025600W -
532751N 0025537W -
532734N 0025532W -
532725N 0025547W -
532726N 0025636W -
532740N 0025641W -
532753N 0025641W -
532802N 0025617W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 86 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.93805,53.4670833333,152.4 -2.9446055556,53.4648444444,152.4 -2.9447194444,53.46123333330001,152.4 -2.9432222222,53.4572638889,152.4 -2.9298333333,53.4570138889,152.4 -2.9254722222,53.4595444444,152.4 -2.926844444399999,53.4641,152.4 -2.9333222222,53.46705,152.4 -2.93805,53.4670833333,152.4 + + + + +
+ + EGRU326 HMP ASKHAM GRANGE + 535551N 0011124W -
535552N 0011041W -
535537N 0011031W -
535520N 0011046W -
535516N 0011105W -
535520N 0011123W -
535539N 0011137W -
535551N 0011124W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 104 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1900611111,53.9308583333,182.88 -1.1936361111,53.9275305556,182.88 -1.1895888889,53.9222666667,182.88 -1.1848388889,53.9211972222,182.88 -1.1794583333,53.9221,182.88 -1.1751583333,53.9269861111,182.88 -1.1780777778,53.9311083333,182.88 -1.1900611111,53.9308583333,182.88 + + + + +
+ + EGRU327 HMP BERWYN + 530233N 0025539W -
530210N 0025453W -
530137N 0025537W -
530159N 0025625W -
530233N 0025539W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 118 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.927375,53.0424444444,182.88 -2.9403833333,53.0330111111,182.88 -2.9270166667,53.0268944444,182.88 -2.9147805556,53.0362027778,182.88 -2.927375,53.0424444444,182.88 + + + + +
+ + EGRU328 HMP BUCKLEY HALL + 533825N 0020916W -
533826N 0020823W -
533805N 0020814W -
533754N 0020816W -
533744N 0020841W -
533758N 0020909W -
533825N 0020916W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 585 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.154525,53.6402944444,304.8 -2.1525222222,53.6327444444,304.8 -2.1448333333,53.6288722222,304.8 -2.1377555556,53.6317027778,304.8 -2.1370972222,53.6348333333,304.8 -2.1397833333,53.6406194444,304.8 -2.154525,53.6402944444,304.8 + + + + +
+ + EGRU329 HMP DONCASTER + 533154N 0010840W -
533130N 0010807W -
533104N 0010843W -
533126N 0010928W -
533154N 0010840W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 55 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1444388889,53.5315583333,152.4 -1.1577666667,53.52399444440001,152.4 -1.1453638889,53.51771944439999,152.4 -1.1354083333,53.5251083333,152.4 -1.1444388889,53.5315583333,152.4 + + + + +
+ + EGRU330 HMP FOREST BANK + 533113N 0021811W -
533102N 0021732W -
533047N 0021730W -
533029N 0021808W -
533056N 0021847W -
533113N 0021811W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 128 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3030138889,53.5202,182.88 -2.3129333333,53.51568333329999,182.88 -2.3022722222,53.5080277778,182.88 -2.2917777778,53.51300833330001,182.88 -2.2921805556,53.5171638889,182.88 -2.3030138889,53.5202,182.88 + + + + +
+ + EGRU331 HMP FULL SUTTON + 535923N 0005234W -
535920N 0005134W -
535842N 0005138W -
535845N 0005239W -
535923N 0005234W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 57 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8760472222,53.9896138889,152.4 -0.8775861111,53.979075,152.4 -0.8606055556000001,53.97820000000001,152.4 -0.8593111110999999,53.98882222219999,152.4 -0.8760472222,53.9896138889,152.4 + + + + +
+ + EGRU332 HMP GARTH/WYMOTT + 534108N 0024604W -
534108N 0024455W -
534103N 0024428W -
534023N 0024424W -
534022N 0024529W -
534033N 0024603W -
534108N 0024604W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 50 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7676833333,53.68546666670001,152.4 -2.7675444444,53.6757666667,152.4 -2.7581694444,53.67288333330001,152.4 -2.7399944444,53.6731444444,152.4 -2.7410666667,53.68416111110001,152.4 -2.7487361111,53.6856027778,152.4 -2.7676833333,53.68546666670001,152.4 + + + + +
+ + EGRU333 HMP HINDLEY + 533127N 0023410W -
533057N 0023356W -
533048N 0023459W -
533119N 0023510W -
533127N 0023410W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 127 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5694444444,53.5242805556,182.88 -2.5862361111,53.5218611111,182.88 -2.5829361111,53.5132916667,182.88 -2.5656388889,53.51574722220001,182.88 -2.5694444444,53.5242805556,182.88 + + + + +
+ + EGRU334 HMP HULL + 534518N 0001815W -
534518N 0001708W -
534458N 0001709W -
534439N 0001732W -
534439N 0001817W -
534518N 0001815W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 17 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3041611111,53.7549277778,152.4 -0.3046055556,53.7440388889,152.4 -0.2920833333,53.74415,152.4 -0.2857472222,53.7494888889,152.4 -0.2854222222,53.75506388889999,152.4 -0.3041611111,53.7549277778,152.4 + + + + +
+ + EGRU335 HMP HUMBER + 534633N 0003818W -
534627N 0003753W -
534605N 0003727W -
534549N 0003759W -
534550N 0003846W -
534617N 0003904W -
534633N 0003818W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 71 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6382388889,53.7757222222,152.4 -0.6510861111,53.7714277778,152.4 -0.6461416667,53.7639166667,152.4 -0.6329944444,53.7635388889,152.4 -0.6240388889,53.7680166667,152.4 -0.6313444444,53.7741194444,152.4 -0.6382388889,53.7757222222,152.4 + + + + +
+ + EGRU336 HMP LEEDS + 534805N 0013438W -
534758N 0013410W -
534733N 0013407W -
534727N 0013438W -
534739N 0013509W -
534801N 0013501W -
534805N 0013438W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 245 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5773277778,53.8012805556,213.36 -1.5836694444,53.8002944444,213.36 -1.5858305556,53.7941166667,213.36 -1.5771444444,53.7907694444,213.36 -1.5686861111,53.79243611110001,213.36 -1.5694972222,53.7994833333,213.36 -1.5773277778,53.8012805556,213.36 + + + + +
+ + EGRU337 HMP LINCOLN + 531426N 0003115W -
531422N 0003038W -
531400N 0003032W -
531350N 0003046W -
531353N 0003122W -
531401N 0003132W -
531415N 0003132W -
531426N 0003115W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Restricted Area (EGR313) Waddington and HMPPS.
Contact: RAF Waddington Station Ops 01522-726532 or email: wad-stationops@mod.gov.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 163 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5207194444,53.24055,182.88 -0.5256916667,53.2375583333,182.88 -0.5254333333,53.23372777779999,182.88 -0.5227000000000001,53.2314527778,182.88 -0.5127777778,53.23064444440001,182.88 -0.5089916667,53.2332305556,182.88 -0.5106000000000001,53.2393777778,182.88 -0.5207194444,53.24055,182.88 + + + + +
+ + EGRU338 HMP LINDHOLME/MOORLAND + 533313N 0005850W -
533311N 0005732W -
533254N 0005713W -
533214N 0005733W -
533219N 0005853W -
533313N 0005850W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 29 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9806055556,53.5535833333,152.4 -0.9814833333,53.53871666669999,152.4 -0.9591083333,53.5372694444,152.4 -0.9536722222,53.54842222220001,152.4 -0.9588222222,53.5530611111,152.4 -0.9806055556,53.5535833333,152.4 + + + + +
+ + EGRU339 HMP LIVERPOOL + 532740N 0025848W -
532750N 0025753W -
532742N 0025741W -
532719N 0025731W -
532706N 0025834W -
532740N 0025848W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.980019444399999,53.4611777778,182.88 -2.9762333333,53.4516722222,182.88 -2.9585833333,53.4552138889,182.88 -2.9614138889,53.4616583333,182.88 -2.964752777799999,53.4638861111,182.88 -2.980019444399999,53.4611777778,182.88 + + + + +
+ + EGRU340 HMP LOWDHAM GRANGE + 530115N 0010219W -
530110N 0010156W -
530055N 0010149W -
530039N 0010203W -
530035N 0010234W -
530052N 0010258W -
530108N 0010247W -
530115N 0010219W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 281 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0387222222,53.0207638889,213.36 -1.04635,53.0188944444,213.36 -1.0495444444,53.0145166667,213.36 -1.0426388889,53.0096305556,213.36 -1.0340305556,53.010775,213.36 -1.0301833333,53.0151972222,213.36 -1.0323027778,53.019425,213.36 -1.0387222222,53.0207638889,213.36 + + + + +
+ + EGRU341 HMP MANCHESTER + 533000N 0021509W -
532957N 0021446W -
532943N 0021414W -
532929N 0021413W -
532919N 0021435W -
532916N 0021448W -
532920N 0021507W -
532937N 0021520W -
533000N 0021509W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 153 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2525083333,53.5000555556,182.88 -2.2556861111,53.4935416667,182.88 -2.2519944444,53.4887888889,182.88 -2.2465805556,53.4877444444,182.88 -2.242975,53.4886138889,182.88 -2.2370361111,53.4915083333,182.88 -2.2373111111,53.4954055556,182.88 -2.246225,53.4992083333,182.88 -2.2525083333,53.5000555556,182.88 + + + + +
+ + EGRU342 HMP MORTON HALL + 531026N 0004128W -
531021N 0004043W -
530946N 0004034W -
530938N 0004054W -
530942N 0004135W -
531008N 0004144W -
531026N 0004128W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 79 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6910888889,53.1738,152.4 -0.6956666667,53.16876666669999,152.4 -0.6930166667,53.1615611111,152.4 -0.6816,53.16058055559999,152.4 -0.6761861111,53.1627138889,152.4 -0.6785611110999999,53.1725222222,152.4 -0.6910888889,53.1738,152.4 + + + + +
+ + EGRU343 HMP NEW HALL + 533826N 0013700W -
533826N 0013620W -
533811N 0013613W -
533753N 0013618W -
533752N 0013640W -
533800N 0013716W -
533818N 0013719W -
533826N 0013700W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 458 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6165638889,53.6405861111,274.32 -1.6218666667,53.63846944439999,274.32 -1.6211555556,53.63321944439999,274.32 -1.6110805556,53.6311361111,274.32 -1.6048611111,53.6312833333,274.32 -1.6036416667,53.63649444440001,274.32 -1.6056888889,53.6405777778,274.32 -1.6165638889,53.6405861111,274.32 + + + + +
+ + EGRU344 HMP PRESTON + 534606N 0024105W -
534537N 0024043W -
534525N 0024124W -
534538N 0024149W -
534555N 0024139W -
534606N 0024105W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 147 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6846,53.7683555556,182.88 -2.6940861111,53.7653888889,182.88 -2.6968777778,53.7606694444,182.88 -2.6900666667,53.75699722219999,182.88 -2.6785833333,53.760175,182.88 -2.6846,53.7683555556,182.88 + + + + +
+ + EGRU345 HMP RANBY + 531943N 0005946W -
531922N 0005920W -
531858N 0005925W -
531903N 0010035W -
531926N 0010034W -
531943N 0005946W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 153 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9960666667,53.32866666670001,182.88 -1.009525,53.32382777779999,182.88 -1.0096972222,53.31741388890001,182.88 -0.9902694444,53.31601944439999,182.88 -0.9887527778,53.3227777778,182.88 -0.9960666667,53.32866666670001,182.88 + + + + +
+ + EGRU346 HMP RISLEY + 532638N 0023135W -
532635N 0023109W -
532624N 0023059W -
532602N 0023050W -
532558N 0023204W -
532625N 0023154W -
532638N 0023135W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 126 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5262638889,53.4438638889,182.88 -2.5317916667,53.4401555556,182.88 -2.5344305556,53.4327611111,182.88 -2.5137916667,53.4338666667,182.88 -2.5162555556,53.43994166670001,182.88 -2.5190416667,53.44307499999999,182.88 -2.5262638889,53.4438638889,182.88 + + + + +
+ + EGRU347 HMP STYAL + 532043N 0021412W -
532031N 0021342W -
532010N 0021357W -
532005N 0021442W -
532019N 0021500W -
532038N 0021441W -
532043N 0021412W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 271 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2365972222,53.34522222220001,213.36 -2.2448416667,53.34383055559999,213.36 -2.2500166667,53.3386916667,213.36 -2.2451083333,53.3347666667,213.36 -2.2324833333,53.33602222220001,213.36 -2.2282388889,53.3418388889,213.36 -2.2365972222,53.34522222220001,213.36 + + + + +
+ + EGRU348 HMP WAKEFIELD + 534112N 0013105W -
534118N 0013027W -
534051N 0012947W -
534035N 0013042W -
534054N 0013104W -
534112N 0013105W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5180833333,53.68662777779999,182.88 -1.5176888889,53.6818027778,182.88 -1.511725,53.67625,182.88 -1.4965,53.68073055560001,182.88 -1.5075333333,53.6883444444,182.88 -1.5180833333,53.68662777779999,182.88 + + + + +
+ + EGRU349 HMP WEALSTUN + 535520N 0011957W -
535515N 0011917W -
535456N 0011909W -
535432N 0011932W -
535432N 0011955W -
535443N 0012021W -
535454N 0012018W -
535506N 0012011W -
535520N 0011957W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 104 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.33255,53.92216111110001,182.88 -1.3364861111,53.9183027778,182.88 -1.3382055556,53.9151166667,182.88 -1.3392722222,53.9119583333,182.88 -1.3319944444,53.9089,182.88 -1.3256611111,53.9087638889,182.88 -1.3190305556,53.9155222222,182.88 -1.3214888889,53.9207194444,182.88 -1.33255,53.92216111110001,182.88 + + + + +
+ + EGRU350 HMP WERRINGTON + 530135N 0020538W -
530140N 0020507W -
530131N 0020450W -
530108N 0020437W -
530100N 0020530W -
530118N 0020540W -
530135N 0020538W
Upper limit: 1300 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 834 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0938416667,53.02645833329999,396.24 -2.094375,53.02160555559999,396.24 -2.0916583333,53.0165722222,396.24 -2.0768916667,53.01876111109999,396.24 -2.0805333333,53.0252555556,396.24 -2.0854083333,53.0276388889,396.24 -2.0938416667,53.02645833329999,396.24 + + + + +
+ + EGRU351 HMP WETHERBY + 535628N 0012218W -
535633N 0012138W -
535557N 0012124W -
535551N 0012229W -
535616N 0012241W -
535623N 0012221W -
535628N 0012218W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 89 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3716555556,53.9410944444,152.4 -1.3724861111,53.93978888889999,152.4 -1.3780666667,53.9377611111,152.4 -1.3747638889,53.93088611110001,152.4 -1.3567138889,53.93245555560001,152.4 -1.3605833333,53.9424916667,152.4 -1.3716555556,53.9410944444,152.4 + + + + +
+ + EGRU401A ENNISKILLEN/ST ANGELO + A circle, 2 NM radius, centred at 542355N 0073907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.651894444400001,54.4319645097,609.6 -7.6577631133,54.4317880028,609.6 -7.6635694228,54.4312603575,609.6 -7.669251681100001,54.4303871803,609.6 -7.674749523699999,54.4291777486,609.6 -7.680004558999999,54.4276449115,609.6 -7.6849609919,54.4258049525,609.6 -7.6895662193,54.42367741499999,609.6 -7.6937713903,54.4212848941,609.6 -7.697531925499999,54.41865279449999,609.6 -7.7008079893,54.41580906029999,609.6 -7.7035649119,54.4127838759,609.6 -7.7057735534,54.4096093453,609.6 -7.7074106097,54.40631914959999,609.6 -7.7084588548,54.4029481892,609.6 -7.7089073179,54.39953221220001,609.6 -7.7087513939,54.3961074356,609.6 -7.7079928858,54.39271016040001,609.6 -7.706639979299999,54.38937638760001,609.6 -7.7047071497,54.3861414363,609.6 -7.7022150032,54.38303957069999,609.6 -7.6991900532,54.380103638,609.6 -7.6956644351,54.3773647213,609.6 -7.691675563,54.37485181190001,609.6 -7.6872657315,54.372591504,609.6 -7.6824816662,54.3706077142,609.6 -7.677374029799999,54.3689214302,609.6 -7.6719968874,54.3675504896,609.6 -7.6664071357,54.366509393,609.6 -7.660663905299999,54.36580915089999,609.6 -7.6548279383,54.3654571688,609.6 -7.6489609506,54.3654571688,609.6 -7.6431249836,54.36580915089999,609.6 -7.6373817532,54.366509393,609.6 -7.6317920015,54.3675504896,609.6 -7.626414859,54.3689214302,609.6 -7.6213072227,54.3706077142,609.6 -7.6165231574,54.372591504,609.6 -7.6121133258,54.37485181190001,609.6 -7.6081244538,54.3773647213,609.6 -7.6045988357,54.380103638,609.6 -7.6015738857,54.38303957069999,609.6 -7.5990817392,54.3861414363,609.6 -7.5971489096,54.38937638760001,609.6 -7.595796003,54.39271016040001,609.6 -7.5950374949,54.3961074356,609.6 -7.594881571000001,54.39953221220001,609.6 -7.5953300341,54.4029481892,609.6 -7.5963782792,54.40631914959999,609.6 -7.5980153355,54.4096093453,609.6 -7.600223977,54.4127838759,609.6 -7.6029808996,54.41580906029999,609.6 -7.6062569634,54.41865279449999,609.6 -7.610017498500001,54.4212848941,609.6 -7.6142226696,54.42367741499999,609.6 -7.618827897,54.4258049525,609.6 -7.6237843299,54.4276449115,609.6 -7.6290393652,54.4291777486,609.6 -7.6345372078,54.4303871803,609.6 -7.6402194661,54.4312603575,609.6 -7.6460257756,54.4317880028,609.6 -7.651894444400001,54.4319645097,609.6 + + + + +
+ + EGRU401B ENNISKILLEN/ST ANGELO RWY 14 + 542602N 0074247W -
542623N 0074205W -
542536N 0074057W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to
542515N 0074139W -
542602N 0074247W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.713088888899999,54.4338694444,609.6 -7.694273,54.4209643056,609.6 -7.6906578306,54.4231026591,609.6 -7.6867264144,54.42504212379999,609.6 -7.6825108056,54.4267668889,609.6 -7.7013388889,54.4396833333,609.6 -7.713088888899999,54.4338694444,609.6 + + + + +
+ + EGRU401C ENNISKILLEN/ST ANGELO RWY 32 + 542152N 0073531W -
542131N 0073613W -
542214N 0073716W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to
542235N 0073634W -
542152N 0073531W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.591830555599999,54.36440277780001,609.6 -7.6093981667,54.37650480560001,609.6 -7.61299728,54.3743600838,609.6 -7.6169125119,54.3724133666,609.6 -7.621112,54.3706804722,609.6 -7.6035555556,54.3585888889,609.6 -7.591830555599999,54.36440277780001,609.6 + + + + +
+ + EGRU402A BELFAST ALDERGROVE + A circle, 2.5 NM radius, centred at 543927N 0061257W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2158333333,54.69909270639999,609.6 -6.2224594592,54.6989150989,609.6 -6.229028880999999,54.698383796,609.6 -6.2354853842,54.6975033443,609.6 -6.2417737294,54.69628127790001,609.6 -6.2478401287,54.6947280529,609.6 -6.2536327092,54.69285695770001,609.6 -6.2591019599,54.6906839982,609.6 -6.2642011568,54.6882277598,609.6 -6.2688867638,54.6855092472,609.6 -6.2731188056,54.68255170359999,609.6 -6.2768612078,54.6793804105,609.6 -6.2800821046,54.6760224706,609.6 -6.2827541076,54.672506575,609.6 -6.284854537200001,54.6688627568,609.6 -6.2863656112,54.6651221334,609.6 -6.287274592499999,54.6613166408,609.6 -6.2875738922,54.6574787594,609.6 -6.2872611287,54.6536412373,609.6 -6.286339141999999,54.6498368101,609.6 -6.284815964100001,54.6460979221,609.6 -6.2827047442,54.6424564499,609.6 -6.2800236317,54.6389434314,609.6 -6.2767956168,54.6355888016,609.6 -6.273048329999999,54.6324211387,609.6 -6.268813803699999,54.62946742190001,609.6 -6.2641281966,54.6267528025,609.6 -6.2590314843,54.6243003909,609.6 -6.253567118099999,54.6221310617,609.6 -6.247781655799999,54.62026327660001,609.6 -6.2417243659,54.6187129286,609.6 -6.235446811099999,54.6174932083,609.6 -6.2290024118,54.616614492,609.6 -6.2224459954,54.6160842545,609.6 -6.2158333333,54.6159070062,609.6 -6.2092206713,54.6160842545,609.6 -6.2026642549,54.616614492,609.6 -6.196219855600001,54.6174932083,609.6 -6.1899423008,54.6187129286,609.6 -6.183885010900001,54.62026327660001,609.6 -6.178099548500001,54.6221310617,609.6 -6.1726351824,54.6243003909,609.6 -6.1675384701,54.6267528025,609.6 -6.162852863000001,54.62946742190001,609.6 -6.158618336699999,54.6324211387,609.6 -6.1548710499,54.6355888016,609.6 -6.151643035,54.6389434314,609.6 -6.1489619225,54.6424564499,609.6 -6.1468507026,54.6460979221,609.6 -6.145327524599999,54.6498368101,609.6 -6.144405538,54.6536412373,609.6 -6.1440927744,54.6574787594,609.6 -6.144392074200001,54.6613166408,609.6 -6.1453010555,54.6651221334,609.6 -6.146812129499999,54.6688627568,609.6 -6.148912559,54.672506575,609.6 -6.151584562100001,54.6760224706,609.6 -6.1548054589,54.6793804105,609.6 -6.1585478611,54.68255170359999,609.6 -6.1627799028,54.6855092472,609.6 -6.167465509900001,54.6882277598,609.6 -6.1725647068,54.6906839982,609.6 -6.1780339574,54.69285695770001,609.6 -6.183826538,54.6947280529,609.6 -6.1898929372,54.69628127790001,609.6 -6.1961812825,54.6975033443,609.6 -6.202637785700001,54.698383796,609.6 -6.2092072075,54.6989150989,609.6 -6.2158333333,54.69909270639999,609.6 + + + + +
+ + EGRU402B BELFAST ALDERGROVE RWY 07 + 543745N 0061808W -
543815N 0061831W -
543839N 0061702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
543810N 0061638W -
543745N 0061808W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3021944444,54.6292277778,609.6 -6.2772079722,54.63597916669999,609.6 -6.2797248099,54.63860010039999,609.6 -6.2819096729,54.6413194151,609.6 -6.283751166700001,54.6441229722,609.6 -6.3087138889,54.6373777778,609.6 -6.3021944444,54.6292277778,609.6 + + + + +
+ + EGRU402C BELFAST ALDERGROVE RWY 25 + 544109N 0060745W -
544039N 0060721W -
544015N 0060852W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
544044N 0060916W -
544109N 0060745W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.129130555600001,54.68573888889999,609.6 -6.1543686389,54.6789653889,609.6 -6.1518605176,54.6763409319,609.6 -6.1496856953,54.67361848979999,609.6 -6.147855416699999,54.67081225,609.6 -6.1225944444,54.6775916667,609.6 -6.129130555600001,54.68573888889999,609.6 + + + + +
+ + EGRU402D BELFAST ALDERGROVE RWY 17 + 544157N 0061536W -
544207N 0061443W -
544146N 0061431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
544131N 0061521W -
544157N 0061536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2600159167,54.6992365556,609.6 -6.255936416699999,54.6919939444,609.6 -6.2514765225,54.69360131199999,609.6 -6.246825361899999,54.69501532780001,609.6 -6.2420078889,54.69622841670001,609.6 -6.2452674167,54.70201877779999,609.6 -6.2600159167,54.6992365556,609.6 + + + + +
+ + EGRU402E BELFAST ALDERGROVE RWY 35 + 543604N 0061119W -
543554N 0061212W -
543657N 0061247W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
543702N 0061152W -
543604N 0061119W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.188672249999999,54.6012328056,609.6 -6.1976555556,54.61726572220001,609.6 -6.2027725007,54.6166028186,609.6 -6.207959133699999,54.6161585674,609.6 -6.213187777799999,54.6159353333,609.6 -6.2033843056,54.59845055560001,609.6 -6.188672249999999,54.6012328056,609.6 + + + + +
+ + EGRU403A BELFAST/CITY + A circle, 2 NM radius, centred at 543705N 0055221W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.8725,54.6513299617,609.6 -5.8784002309,54.65115346009999,609.6 -5.8842377659,54.6506258306,609.6 -5.8899505801,54.6497526798,609.6 -5.8954779834,54.64854328479999,609.6 -5.9007612692,54.6470104947,609.6 -5.905744341999999,54.6451705926,609.6 -5.9103743152,54.64304312179999,609.6 -5.9146020751,54.6406506769,609.6 -5.9183828029,54.63801866239999,609.6 -5.9216764494,54.6351750215,609.6 -5.9244481591,54.63214993830001,609.6 -5.9266686364,54.62897551569999,609.6 -5.928314453399999,54.62568543410001,609.6 -5.929368292899999,54.62231459280001,609.6 -5.9298191266,54.6188987388,609.6 -5.929662326399999,54.6154740878,609.6 -5.928899706500001,54.6120769396,609.6 -5.927539498300001,54.60874329349999,609.6 -5.9255962562,54.6055084673,609.6 -5.9230906984,54.6024067236,609.6 -5.920049481799999,54.5994709081,609.6 -5.916504915099999,54.5967321021,609.6 -5.912494614,54.5942192958,609.6 -5.9080611001,54.5919590816,609.6 -5.90325135,54.5899753748,609.6 -5.898116298,54.588289162,609.6 -5.892710298600001,54.5869182798,609.6 -5.8870905533,54.5858772276,609.6 -5.8813165087,54.5851770156,609.6 -5.875449231699999,54.58482504860001,609.6 -5.8695507683,54.58482504860001,609.6 -5.863683491299999,54.5851770156,609.6 -5.857909446700001,54.5858772276,609.6 -5.8522897014,54.5869182798,609.6 -5.846883702,54.588289162,609.6 -5.84174865,54.5899753748,609.6 -5.836938899899999,54.5919590816,609.6 -5.832505386,54.5942192958,609.6 -5.8284950849,54.5967321021,609.6 -5.824950518200001,54.5994709081,609.6 -5.8219093016,54.6024067236,609.6 -5.8194037438,54.6055084673,609.6 -5.8174605017,54.60874329349999,609.6 -5.8161002935,54.6120769396,609.6 -5.8153376736,54.6154740878,609.6 -5.815180873400001,54.6188987388,609.6 -5.815631707100001,54.62231459280001,609.6 -5.8166855466,54.62568543410001,609.6 -5.8183313636,54.62897551569999,609.6 -5.820551840900001,54.63214993830001,609.6 -5.823323550599999,54.6351750215,609.6 -5.826617197099999,54.63801866239999,609.6 -5.8303979249,54.6406506769,609.6 -5.8346256848,54.64304312179999,609.6 -5.839255658,54.6451705926,609.6 -5.844238730799999,54.6470104947,609.6 -5.8495220166,54.64854328479999,609.6 -5.8550494199,54.6497526798,609.6 -5.8607622341,54.6506258306,609.6 -5.8665997691,54.65115346009999,609.6 -5.8725,54.6513299617,609.6 + + + + +
+ + EGRU403B BELFAST/CITY RWY 04 + 543421N 0055503W -
543440N 0055549W -
543537N 0055441W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to
543518N 0055355W -
543421N 0055503W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.9174916667,54.5725666667,609.6 -5.898566388899999,54.5884211389,609.6 -5.9030612095,54.5899055038,609.6 -5.9073076397,54.5916190103,609.6 -5.9112711389,54.5935477222,609.6 -5.9301944444,54.5776916667,609.6 -5.9174916667,54.5725666667,609.6 + + + + +
+ + EGRU403C BELFAST/CITY RWY 22 + 543951N 0054936W -
543933N 0054850W -
543833N 0055002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to
543852N 0055047W -
543951N 0054936W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.8266055556,54.6643027778,609.6 -5.8464906111,54.6477122778,609.6 -5.8419875834,54.6462309714,609.6 -5.8377334708,54.6445201629,609.6 -5.8337629444,54.6425938056,609.6 -5.813875000000001,54.6591833333,609.6 -5.8266055556,54.6643027778,609.6 + + + + +
+ + EGRU404A NEWTOWNARDS + A circle, 2 NM radius, centred at 543452N 0054131W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6919444444,54.6143857216,609.6 -5.697839330000001,54.6142092191,609.6 -5.7036715766,54.61368158700001,609.6 -5.709379215799999,54.6128084317,609.6 -5.7149016127,54.6115990305,609.6 -5.720180114,54.6100662325,609.6 -5.725158675,54.6082263209,609.6 -5.7297844573,54.6060988389,609.6 -5.7340083916,54.60370638119999,609.6 -5.737785699500001,54.6010743524,609.6 -5.741076368299999,54.59823069580001,609.6 -5.7438455736,54.59520559560001,609.6 -5.746064046399999,54.5920311548,609.6 -5.7477083797,54.5887410541,609.6 -5.748761271699999,54.5853701927,609.6 -5.749211704000001,54.581954318,609.6 -5.7490550522,54.5785296459,609.6 -5.7482931288,54.5751324763,609.6 -5.7469341571,54.5717988089,609.6 -5.744992678500001,54.5685639616,609.6 -5.7424893921,54.5654621975,609.6 -5.7394509304,54.5625263622,609.6 -5.7359095728,54.55978753760001,609.6 -5.7319029009,54.5572747139,609.6 -5.727473397900001,54.55501448390001,609.6 -5.7226679978,54.5530307632,609.6 -5.7175375889,54.5513445384,609.6 -5.712136476699999,54.5499736463,609.6 -5.7065218111,54.5489325867,609.6 -5.7007529851,54.5482323696,609.6 -5.6948910108,54.5478804001,609.6 -5.6889978781,54.5478804001,609.6 -5.6831359038,54.5482323696,609.6 -5.6773670778,54.5489325867,609.6 -5.6717524122,54.5499736463,609.6 -5.6663513,54.5513445384,609.6 -5.6612208911,54.5530307632,609.6 -5.656415491,54.55501448390001,609.6 -5.651985987899999,54.5572747139,609.6 -5.647979316099999,54.55978753760001,609.6 -5.6444379585,54.5625263622,609.6 -5.641399496799999,54.5654621975,609.6 -5.6388962103,54.5685639616,609.6 -5.6369547318,54.5717988089,609.6 -5.635595760099999,54.5751324763,609.6 -5.634833836699999,54.5785296459,609.6 -5.634677184900001,54.581954318,609.6 -5.6351276172,54.5853701927,609.6 -5.636180509199999,54.5887410541,609.6 -5.6378248425,54.5920311548,609.6 -5.6400433153,54.59520559560001,609.6 -5.6428125206,54.59823069580001,609.6 -5.6461031894,54.6010743524,609.6 -5.6498804973,54.60370638119999,609.6 -5.6541044316,54.6060988389,609.6 -5.6587302139,54.6082263209,609.6 -5.6637087749,54.6100662325,609.6 -5.6689872762,54.6115990305,609.6 -5.6745096731,54.6128084317,609.6 -5.680217312300001,54.61368158700001,609.6 -5.6860495589,54.6142092191,609.6 -5.6919444444,54.6143857216,609.6 + + + + +
+ + EGRU404B NEWTOWNARDS RWY 03 + 543214N 0054343W -
543231N 0054430W -
543319N 0054340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543302N 0054253W -
543214N 0054343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7285722222,54.5372,609.6 -5.7146738611,54.5505698333,609.6 -5.719318224,54.5518842841,609.6 -5.7237401423,54.5534366053,609.6 -5.7279036667,54.5552141667,609.6 -5.741791666700001,54.54185,609.6 -5.7285722222,54.5372,609.6 + + + + +
+ + EGRU404C NEWTOWNARDS RWY 21 + 543727N 0053922W -
543710N 0053834W -
543625N 0053921W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543642N 0054009W -
543727N 0053922W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6560305556,54.6242111111,609.6 -5.6691476389,54.6116395833,609.6 -5.6644993349,54.6103214286,609.6 -5.660075022000001,54.6087652411,609.6 -5.6559107778,54.6069837222,609.6 -5.642783333299999,54.6195611111,609.6 -5.6560305556,54.6242111111,609.6 + + + + +
+ + EGRU404D NEWTOWNARDS RWY 08 + 543356N 0054615W -
543428N 0054627W -
543440N 0054456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543408N 0054443W -
543356N 0054615W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.770788888900001,54.56556388890001,609.6 -5.7453074167,54.5690223611,609.6 -5.746967770199999,54.5718659434,609.6 -5.7481803273,54.57478490070001,609.6 -5.748935138900001,54.5777554722,609.6 -5.7742916667,54.5743138889,609.6 -5.770788888900001,54.56556388890001,609.6 + + + + +
+ + EGRU404E NEWTOWNARDS RWY 26 + 543545N 0053655W -
543513N 0053642W -
543502N 0053806W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543534N 0053818W -
543545N 0053655W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6151472222,54.5958166667,609.6 -5.6382448611,54.5927102222,609.6 -5.636664830199999,54.5898510472,609.6 -5.635535265300001,54.5869207834,609.6 -5.634865277800001,54.5839433056,609.6 -5.6116416667,54.5870666667,609.6 -5.6151472222,54.5958166667,609.6 + + + + +
+ + EGRU404F NEWTOWNARDS RWY 15 + 543716N 0054418W -
543733N 0054330W -
543645N 0054241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543630N 0054331W -
543716N 0054418W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.738344444400001,54.6211611111,609.6 -5.7251928056,54.6082122222,609.6 -5.7208435871,54.60984465680001,609.6 -5.716257972799999,54.6112424062,609.6 -5.711473444400001,54.6123940278,609.6 -5.7250027778,54.6257194444,609.6 -5.738344444400001,54.6211611111,609.6 + + + + +
+ + EGRU404G NEWTOWNARDS RWY 33 + 543241N 0053834W -
543224N 0053922W -
543304N 0054002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543322N 0053916W -
543241N 0053834W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.642805555599999,54.5446027778,609.6 -5.6543445833,54.556013,609.6 -5.6583959388,54.5541442047,609.6 -5.662720605,54.5524954264,609.6 -5.6672833056,54.5510800833,609.6 -5.656119444400001,54.5400444444,609.6 -5.642805555599999,54.5446027778,609.6 + + + + +
+ + EGRU406A WALNEY + A circle, 2 NM radius, centred at 540752N 0031548W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2632277778,54.1643771067,609.6 -3.2690585169,54.1642005933,609.6 -3.274827301300001,54.1636729286,609.6 -3.280472839,54.1627997191,609.6 -3.285935157,54.1615902424,609.6 -3.291156242,54.1600573477,609.6 -3.2960806603,54.1582173188,609.6 -3.3006561493,54.1560896996,609.6 -3.3048341738,54.1536970853,609.6 -3.3085704421,54.1510648816,609.6 -3.3118253756,54.1482210329,609.6 -3.3145645274,54.1451957247,609.6 -3.3167589447,54.14202106170001,609.6 -3.3183854724,54.1387307264,609.6 -3.319426994,54.1353596202,609.6 -3.3198726078,54.1319434927,609.6 -3.3197177365,54.1285185624,609.6 -3.3189641693,54.125121132,609.6 -3.3176200374,54.1217872042,609.6 -3.3156997208,54.1185520999,609.6 -3.3132236912,54.1154500854,609.6 -3.3102182896,54.1125140096,609.6 -3.306715442999999,54.1097749575,609.6 -3.3027523237,54.1072619224,609.6 -3.2983709527,54.1050015,609.6 -3.2936177545,54.1030176089,609.6 -3.2885430655,54.1013312379,609.6 -3.2832006024,54.0999602261,609.6 -3.277646896399999,54.0989190751,609.6 -3.271940697799999,54.0982187963,609.6 -3.2661423583,54.0978667957,609.6 -3.2603131973,54.0978667957,609.6 -3.254514857799999,54.0982187963,609.6 -3.2488086591,54.0989190751,609.6 -3.2432549531,54.0999602261,609.6 -3.2379124901,54.1013312379,609.6 -3.2328378011,54.1030176089,609.6 -3.2280846029,54.1050015,609.6 -3.2237032319,54.1072619224,609.6 -3.2197401125,54.1097749575,609.6 -3.216237265999999,54.1125140096,609.6 -3.2132318643,54.1154500854,609.6 -3.2107558347,54.1185520999,609.6 -3.2088355182,54.1217872042,609.6 -3.2074913862,54.125121132,609.6 -3.2067378191,54.1285185624,609.6 -3.2065829477,54.1319434927,609.6 -3.2070285615,54.1353596202,609.6 -3.2080700832,54.1387307264,609.6 -3.2096966109,54.14202106170001,609.6 -3.2118910282,54.1451957247,609.6 -3.21463018,54.1482210329,609.6 -3.2178851135,54.1510648816,609.6 -3.221621381799999,54.1536970853,609.6 -3.2257994062,54.1560896996,609.6 -3.230374895200001,54.1582173188,609.6 -3.2352993136,54.1600573477,609.6 -3.2405203986,54.1615902424,609.6 -3.2459827166,54.1627997191,609.6 -3.2516282543,54.1636729286,609.6 -3.257397038600001,54.1642005933,609.6 -3.2632277778,54.1643771067,609.6 + + + + +
+ + EGRU406B WALNEY RWY 17 + 541032N 0031742W -
541040N 0031649W -
540949N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to
540939N 0031720W -
541032N 0031742W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.295125,54.1756527778,609.6 -3.2888458333,54.1607845278,609.6 -3.2841622035,54.1620244874,609.6 -3.2793062909,54.1630103456,609.6 -3.2743180556,54.163734,609.6 -3.2802583333,54.17781111109999,609.6 -3.295125,54.1756527778,609.6 + + + + +
+ + EGRU406C WALNEY RWY 35 + 540454N 0031423W -
540447N 0031517W -
540552N 0031544W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to
540557N 0031450W -
540454N 0031423W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2398166667,54.08177777780001,609.6 -3.2471365833,54.0991938333,609.6 -3.25211691,54.0984692599,609.6 -3.2571882587,54.0980124281,609.6 -3.2623090833,54.09782708329999,609.6 -3.254649999999999,54.0796194444,609.6 -3.2398166667,54.08177777780001,609.6 + + + + +
+ + EGRU408A LEEMING + A circle, 2.5 NM radius, centred at 541733N 0013207W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5352777778,54.3340952335,609.6 -1.5418450861,54.33391761759999,609.6 -1.548356196,54.3333862896,609.6 -1.5547553941,54.33250579620001,609.6 -1.5609879334,54.3312836713,609.6 -1.567000505,54.3297303713,609.6 -1.572741698,54.3278591848,609.6 -1.5781624417,54.3256861177,609.6 -1.5832164274,54.3232297559,609.6 -1.5878605055,54.3205111044,609.6 -1.5920550547,54.3175534068,609.6 -1.5957643201,54.3143819454,609.6 -1.5989567169,54.3110238238,609.6 -1.6016050982,54.3075077339,609.6 -1.6036869829,54.30386371000001,609.6 -1.6051847444,54.300122871,609.6 -1.6060857555,54.2963171542,609.6 -1.6063824916,54.292479042,609.6 -1.6060725893,54.2886412841,609.6 -1.6051588604,54.28483661849999,609.6 -1.6036492625,54.28109749150001,609.6 -1.6015568259,54.27745578219999,609.6 -1.5988995367,54.2739425307,609.6 -1.595700179,54.2705876747,609.6 -1.5919861371,54.2674197949,609.6 -1.5877891582,54.26446587280001,609.6 -1.5831450801,54.26175106209999,609.6 -1.578093524,54.2592984758,609.6 -1.5726775569,54.2571289903,609.6 -1.5669433247,54.2552610693,609.6 -1.5609396611,54.2537106078,609.6 -1.5547176737,54.2524907976,609.6 -1.5483303119,54.2516120162,609.6 -1.5418319199,54.25108173930001,609.6 -1.5352777778,54.25090447780001,609.6 -1.5287236356,54.25108173930001,609.6 -1.5222252436,54.2516120162,609.6 -1.5158378819,54.2524907976,609.6 -1.5096158945,54.2537106078,609.6 -1.5036122309,54.2552610693,609.6 -1.4978779987,54.2571289903,609.6 -1.4924620315,54.2592984758,609.6 -1.4874104755,54.26175106209999,609.6 -1.4827663974,54.26446587280001,609.6 -1.4785694185,54.2674197949,609.6 -1.4748553766,54.2705876747,609.6 -1.4716560189,54.2739425307,609.6 -1.4689987296,54.27745578219999,609.6 -1.466906293,54.28109749150001,609.6 -1.4653966952,54.28483661849999,609.6 -1.4644829663,54.2886412841,609.6 -1.4641730639,54.292479042,609.6 -1.4644698001,54.2963171542,609.6 -1.4653708112,54.300122871,609.6 -1.4668685726,54.30386371000001,609.6 -1.4689504574,54.3075077339,609.6 -1.4715988386,54.3110238238,609.6 -1.4747912355,54.3143819454,609.6 -1.4785005008,54.3175534068,609.6 -1.4826950501,54.3205111044,609.6 -1.4873391281,54.3232297559,609.6 -1.4923931138,54.3256861177,609.6 -1.4978138575,54.3278591848,609.6 -1.5035550505,54.3297303713,609.6 -1.5095676221,54.3312836713,609.6 -1.5158001614,54.33250579620001,609.6 -1.5221993595,54.3333862896,609.6 -1.5287104694,54.33391761759999,609.6 -1.5352777778,54.3340952335,609.6 + + + + +
+ + EGRU408B LEEMING RWY 16 + 542028N 0013452W -
542041N 0013402W -
541955N 0013327W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541942N 0013417W -
542028N 0013452W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5811833333,54.3410333333,609.6 -1.5713919444,54.32833619439999,609.6 -1.5668795474,54.32976553310001,609.6 -1.5622023345,54.3310008906,609.6 -1.5573846944,54.3320358333,609.6 -1.5671611111,54.3447194444,609.6 -1.5811833333,54.3410333333,609.6 + + + + +
+ + EGRU408C LEEMING RWY 34 + 541438N 0012923W -
541425N 0013013W -
541511N 0013048W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541524N 0012958W -
541438N 0012923W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4897166667,54.24400833329999,609.6 -1.4993772778,54.2566009444,609.6 -1.5038895877,54.25518072439999,609.6 -1.5085646991,54.2539544356,609.6 -1.5133783333,54.2529284167,609.6 -1.5037027778,54.24032222220001,609.6 -1.4897166667,54.24400833329999,609.6 + + + + +
+ + EGRU408D LEEMING RWY 03 + 541517N 0013411W -
541532N 0013459W -
541539N 0013453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541521N 0013407W -
541517N 0013411W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5696216944,54.2546920278,609.6 -1.5686279167,54.2557684444,609.6 -1.5730861296,54.2572780563,609.6 -1.5773459603,54.2589728589,609.6 -1.58138525,54.26084375,609.6 -1.5831166667,54.2589676944,609.6 -1.5696216944,54.2546920278,609.6 + + + + +
+ + EGRU408E LEEMING RWY 21 + 542039N 0013015W -
542024N 0012927W -
541944N 0013003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541957N 0013055W -
542039N 0013015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5042563056,54.3442184167,609.6 -1.5152062778,54.3324053056,609.6 -1.5103125354,54.3314499726,609.6 -1.505550483,54.3302895303,609.6 -1.5009450833,54.32893033329999,609.6 -1.4907334444,54.3399428056,609.6 -1.5042563056,54.3442184167,609.6 + + + + +
+ + EGRU409A TEESSIDE INTERNATIONAL + A circle, 2.5 NM radius, centred at 543033N 0012546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4294444444,54.5507603988,609.6 -1.436046508,54.5505827878,609.6 -1.4425920743,54.5500514747,609.6 -1.449025134,54.5491710062,609.6 -1.4552906489,54.547948916,609.6 -1.4613350273,54.5463956606,609.6 -1.4671065851,54.5445245284,609.6 -1.4725559916,54.5423515254,609.6 -1.4776366926,54.539895237,609.6 -1.4823053102,54.5371766681,609.6 -1.4865220138,54.534219062,609.6 -1.4902508599,54.5310477007,609.6 -1.4934600974,54.5276896871,609.6 -1.4961224369,54.5241737127,609.6 -1.4982152799,54.520529811,609.6 -1.4997209079,54.5167891002,609.6 -1.5006266288,54.51298351660001,609.6 -1.5009248799,54.5091455415,609.6 -1.500613287,54.50530792369999,609.6 -1.4996946787,54.5015033997,609.6 -1.4981770565,54.49776441470001,609.6 -1.4960735209,54.4941228462,609.6 -1.4934021546,54.4906097331,609.6 -1.4901858634,54.48725501139999,609.6 -1.4864521771,54.48408726040001,609.6 -1.4822330114,54.48113346020001,609.6 -1.4775643938,54.4784187631,609.6 -1.4724861548,54.4759662806,609.6 -1.4670415886,54.47379688789999,609.6 -1.4612770844,54.4719290476,609.6 -1.4552417328,54.47037865349999,609.6 -1.4489869105,54.4691588966,609.6 -1.442565845,54.4682801539,609.6 -1.4360331662,54.46774990039999,609.6 -1.4294444444,54.4675726466,609.6 -1.4228557227,54.46774990039999,609.6 -1.4163230438,54.4682801539,609.6 -1.4099019784,54.4691588966,609.6 -1.4036471561,54.47037865349999,609.6 -1.3976118045,54.4719290476,609.6 -1.3918473003,54.47379688789999,609.6 -1.3864027341,54.4759662806,609.6 -1.3813244951,54.4784187631,609.6 -1.3766558775,54.48113346020001,609.6 -1.3724367118,54.48408726040001,609.6 -1.3687030255,54.48725501139999,609.6 -1.3654867343,54.4906097331,609.6 -1.362815368,54.4941228462,609.6 -1.3607118324,54.49776441470001,609.6 -1.3591942102,54.5015033997,609.6 -1.3582756019,54.50530792369999,609.6 -1.357964009,54.5091455415,609.6 -1.3582622601,54.51298351660001,609.6 -1.359167981,54.5167891002,609.6 -1.360673609,54.520529811,609.6 -1.362766452,54.5241737127,609.6 -1.3654287915,54.5276896871,609.6 -1.368638029,54.5310477007,609.6 -1.3723668751,54.534219062,609.6 -1.3765835787,54.5371766681,609.6 -1.3812521963,54.539895237,609.6 -1.3863328973,54.5423515254,609.6 -1.3917823038,54.5445245284,609.6 -1.3975538616,54.5463956606,609.6 -1.40359824,54.547948916,609.6 -1.4098637549,54.5491710062,609.6 -1.4162968146,54.5500514747,609.6 -1.4228423809,54.5505827878,609.6 -1.4294444444,54.5507603988,609.6 + + + + +
+ + EGRU409B TEESSIDE INTERNATIONAL RWY 05 + 542807N 0012938W -
542831N 0013016W -
542904N 0012913W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to
542840N 0012836W -
542807N 0012938W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4940166667,54.468525,609.6 -1.4765378333,54.47788497219999,609.6 -1.4802882836,54.4799412982,609.6 -1.4837748599,54.48214957159999,609.6 -1.4869794167,54.48449833330001,609.6 -1.5044444444,54.4751444444,609.6 -1.4940166667,54.468525,609.6 + + + + +
+ + EGRU409C TEESSIDE INTERNATIONAL RWY 23 + 543259N 0012153W -
543235N 0012115W -
543202N 0012219W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to
543226N 0012256W -
543259N 0012153W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3646916667,54.54980277779999,609.6 -1.3822803611,54.5404305,609.6 -1.3785290961,54.53837112879999,609.6 -1.3750432165,54.5361598086,609.6 -1.3718408611,54.5338080556,609.6 -1.3542388889,54.5431861111,609.6 -1.3646916667,54.54980277779999,609.6 + + + + +
+ + EGRU410A TOPCLIFFE + A circle, 2 NM radius, centred at 541220N 0012254W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3816277778,54.2389044702,609.6 -1.3874690187,54.23872795859999,609.6 -1.3932481928,54.2382002993,609.6 -1.3989038975,54.23732709879999,609.6 -1.4043760513,54.2361176346,609.6 -1.4096065363,54.23458475609999,609.6 -1.4145398186,54.2327447467,609.6 -1.4191235415,54.2306171503,609.6 -1.4233090821,54.2282245621,609.6 -1.4270520693,54.2255923874,609.6 -1.4303128533,54.2227485706,609.6 -1.4330569254,54.2197232969,609.6 -1.4352552811,54.21654867090001,609.6 -1.4368847239,54.2132583746,609.6 -1.4379281072,54.209887309,609.6 -1.4383745099,54.2064712235,609.6 -1.4382193472,54.20304633599999,609.6 -1.437464412,54.1996489489,609.6 -1.4361178506,54.1963150643,609.6 -1.4341940696,54.1930800027,609.6 -1.4317135777,54.18997802970001,609.6 -1.4287027635,54.1870419937,609.6 -1.4251936121,54.1843029793,609.6 -1.4212233625,54.1817899792,609.6 -1.4168341115,54.17952958880001,609.6 -1.4120723669,54.17754572590001,609.6 -1.4069885556,54.1758593791,609.6 -1.4016364907,54.1744883872,609.6 -1.3960728045,54.1734472513,609.6 -1.3903563526,54.1727469828,609.6 -1.3845475949,54.1723949873,609.6 -1.3787079606,54.1723949873,609.6 -1.372899203,54.1727469828,609.6 -1.3671827511,54.1734472513,609.6 -1.3616190649,54.1744883872,609.6 -1.356267,54.1758593791,609.6 -1.3511831886,54.17754572590001,609.6 -1.3464214441,54.17952958880001,609.6 -1.342032193,54.1817899792,609.6 -1.3380619434,54.1843029793,609.6 -1.334552792,54.1870419937,609.6 -1.3315419779,54.18997802970001,609.6 -1.329061486,54.1930800027,609.6 -1.3271377049,54.1963150643,609.6 -1.3257911435,54.1996489489,609.6 -1.3250362084,54.20304633599999,609.6 -1.3248810456,54.2064712235,609.6 -1.3253274484,54.209887309,609.6 -1.3263708316,54.2132583746,609.6 -1.3280002745,54.21654867090001,609.6 -1.3301986301,54.2197232969,609.6 -1.3329427022,54.2227485706,609.6 -1.3362034863,54.2255923874,609.6 -1.3399464734,54.2282245621,609.6 -1.3441320141,54.2306171503,609.6 -1.3487157369,54.2327447467,609.6 -1.3536490193,54.23458475609999,609.6 -1.3588795043,54.2361176346,609.6 -1.3643516581,54.23732709879999,609.6 -1.3700073628,54.2382002993,609.6 -1.3757865369,54.23872795859999,609.6 -1.3816277778,54.2389044702,609.6 + + + + +
+ + EGRU410B TOPCLIFFE RWY 02 + 540928N 0012421W -
540940N 0012512W -
541036N 0012434W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541024N 0012343W -
540928N 0012421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.40583975,54.1578682778,609.6 -1.3953372778,54.1733367778,609.6 -1.4002433356,54.1741926445,609.6 -1.4049981522,54.1753043042,609.6 -1.4095630833,54.1766627222,609.6 -1.4200591667,54.16119580559999,609.6 -1.40583975,54.1578682778,609.6 + + + + +
+ + EGRU410C TOPCLIFFE RWY 20 + 541524N 0012119W -
541512N 0012027W -
541405N 0012113W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541417N 0012204W -
541524N 0012119W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3551701389,54.25661588889999,609.6 -1.3679102222,54.2379189722,609.6 -1.3629969339,54.23706249489999,609.6 -1.3582356996,54.23594986559999,609.6 -1.3536653611,54.2345901667,609.6 -1.3409179167,54.2532884167,609.6 -1.3551701389,54.25661588889999,609.6 + + + + +
+ + EGRU410D TOPCLIFFE RWY 13 + 541355N 0012720W -
541421N 0012647W -
541344N 0012520W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541318N 0012553W -
541355N 0012720W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4554805,54.2318486944,609.6 -1.4313874444,54.2216514722,609.6 -1.428721035,54.2242160026,609.6 -1.4256705754,54.2266291543,609.6 -1.4222608889,54.22887125,609.6 -1.4464896111,54.2391268611,609.6 -1.4554805,54.2318486944,609.6 + + + + +
+ + EGRU410E TOPCLIFFE RWY 31 + 541053N 0011838W -
541027N 0011910W -
541059N 0012024W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541125N 0011953W -
541053N 0011838W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3105919444,54.18147461109999,609.6 -1.3312787778,54.1902709444,609.6 -1.3338459199,54.18767256549999,609.6 -1.3368016981,54.185220428,609.6 -1.340122,54.1829344722,609.6 -1.3195703333,54.1741963889,609.6 -1.3105919444,54.18147461109999,609.6 + + + + +
+ + EGRU410F TOPCLIFFE RWY 07 + 541107N 0012746W -
541138N 0012800W -
541155N 0012614W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541124N 0012555W -
541107N 0012746W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4628026944,54.1851534167,609.6 -1.4318126944,54.1900875,609.6 -1.4340062649,54.1928130821,609.6 -1.4357705656,54.1956438446,609.6 -1.4370910556,54.1985565833,609.6 -1.4668027778,54.1938257778,609.6 -1.4628026944,54.1851534167,609.6 + + + + +
+ + EGRU410G TOPCLIFFE RWY 25 + 541311N 0011812W -
541240N 0011758W -
541225N 0011930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541257N 0011939W -
541311N 0011812W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3034665833,54.2197288889,609.6 -1.3276355556,54.21591200000001,609.6 -1.3262713683,54.2130061059,609.6 -1.3253615157,54.2100397783,609.6 -1.3249133611,54.2070373611,609.6 -1.299464,54.2110565833,609.6 -1.3034665833,54.2197288889,609.6 + + + + +
+ + EGRU411A ISLE OF MAN + A circle, 2.7 NM radius, centred at 540500N 0043724W
Upper limit: UNL
Lower limit: SFC
Class: Restricted airspace active H24. Small unmanned aircraft flight not permitted except with the permission of the Isle of Man CAA. Contact caa@gov.im or 01624-682358]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6233333333,54.1282577424,30449.52 -4.6300934172,54.12808175609999,30449.52 -4.6368004237,54.1275551791,30449.52 -4.6434016959,54.1266821455,30449.52 -4.6498454151,54.12546950960001,30449.52 -4.6560810113,54.1239267908,30449.52 -4.6620595627,54.1220660988,30449.52 -4.667734183,54.1199020374,30449.52 -4.6730603909,54.117451589,30449.52 -4.6779964608,54.11473398009999,30449.52 -4.6825037501,54.1117705296,30449.52 -4.6865470027,54.10858448009999,30449.52 -4.6900946234,54.1052008146,30449.52 -4.6931189245,54.1016460595,30449.52 -4.6955963394,54.0979480755,30449.52 -4.6975076042,54.09413583830001,30449.52 -4.6988379044,54.09023921090001,30449.52 -4.6995769864,54.0862887089,30449.52 -4.6997192325,54.0823152611,30449.52 -4.6992637003,54.0783499674,30449.52 -4.6982141239,54.0744238547,30449.52 -4.6965788803,54.0705676349,30449.52 -4.694370918,54.0668114647,30449.52 -4.6916076513,54.06318471040001,30449.52 -4.6883108199,54.0597157192,30449.52 -4.6845063152,54.05643159820001,30449.52 -4.6802239747,54.0533580037,30449.52 -4.675497347,54.050518942,30449.52 -4.6703634275,54.0479365828,30449.52 -4.6648623697,54.0456310874,30449.52 -4.6590371708,54.0436204524,30449.52 -4.6529333379,54.0419203703,30449.52 -4.6465985335,54.04054410820001,30449.52 -4.6400822067,54.0395024049,30449.52 -4.6334352097,54.0388033878,30449.52 -4.6267094045,54.0384525106,30449.52 -4.6199572621,54.0384525106,30449.52 -4.613231457,54.0388033878,30449.52 -4.60658446,54.0395024049,30449.52 -4.6000681332,54.04054410820001,30449.52 -4.5937333288,54.0419203703,30449.52 -4.5876294958,54.0436204524,30449.52 -4.581804297,54.0456310874,30449.52 -4.5763032391,54.0479365828,30449.52 -4.5711693197,54.050518942,30449.52 -4.5664426919,54.0533580037,30449.52 -4.5621603515,54.05643159820001,30449.52 -4.5583558468,54.0597157192,30449.52 -4.5550590154,54.06318471040001,30449.52 -4.5522957487,54.0668114647,30449.52 -4.5500877864,54.0705676349,30449.52 -4.5484525427,54.0744238547,30449.52 -4.5474029664,54.0783499674,30449.52 -4.5469474342,54.0823152611,30449.52 -4.5470896803,54.0862887089,30449.52 -4.5478287623,54.09023921090001,30449.52 -4.5491590625,54.09413583830001,30449.52 -4.5510703273,54.0979480755,30449.52 -4.5535477422,54.1016460595,30449.52 -4.5565720433,54.1052008146,30449.52 -4.560119664,54.10858448009999,30449.52 -4.5641629166,54.1117705296,30449.52 -4.5686702059,54.11473398009999,30449.52 -4.5736062758,54.117451589,30449.52 -4.5789324837,54.1199020374,30449.52 -4.584607104,54.1220660988,30449.52 -4.5905856554,54.1239267908,30449.52 -4.5968212515,54.12546950960001,30449.52 -4.6032649708,54.1266821455,30449.52 -4.609866243,54.1275551791,30449.52 -4.6165732494,54.12808175609999,30449.52 -4.6233333333,54.1282577424,30449.52 + + + + +
+ + EGRU412 ISLE OF MAN PRISON + 542124N 0043154W -
542128N 0043151W -
542129N 0043150W -
542133N 0043143W -
542132N 0043141W -
542117N 0043127W -
542114N 0043143W -
542113N 0043153W -
542116N 0043201W -
542117N 0043201W -
542124N 0043154W
Upper limit: UNL
Lower limit: SFC
Class: Restricted airspace active H24. Contact caa@gov.im or 01624-682358 for further details]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5316583333,54.3567583333,30449.52 -4.5337277778,54.3548138889,30449.52 -4.5336166667,54.3545555556,30449.52 -4.5313527778,54.35362499999999,30449.52 -4.5287194444,54.35375555560001,30449.52 -4.5241055556,54.3547611111,30449.52 -4.5280277778,54.3588777778,30449.52 -4.5287472222,54.35928333330001,30449.52 -4.5304888889,54.35806111109999,30449.52 -4.5308222222,54.3577472222,30449.52 -4.5316583333,54.3567583333,30449.52 + + + + +
+ + EGRU413 HMP DEERBOLT + 543255N 0015600W -
543222N 0015541W -
543214N 0015609W -
543221N 0015700W -
543244N 0015701W -
543255N 0015600W
Upper limit: 1100 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 602 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9334416667,54.5484861111,335.28 -1.9503194444,54.54561666669999,335.28 -1.9500527778,54.5391583333,335.28 -1.9359555556,54.5372027778,335.28 -1.9281472222,54.53937777779999,335.28 -1.9334416667,54.5484861111,335.28 + + + + +
+ + EGRU414 HMP DURHAM + 544641N 0013402W -
544635N 0013340W -
544614N 0013337W -
544602N 0013352W -
544609N 0013429W -
544637N 0013440W -
544641N 0013402W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 196 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5670861111,54.7781138889,182.88 -1.5776388889,54.7768805556,182.88 -1.5746444444,54.7692666667,182.88 -1.5645666667,54.7673194444,182.88 -1.5601888889,54.7706861111,182.88 -1.5609722222,54.77634722219999,182.88 -1.5670861111,54.7781138889,182.88 + + + + +
+ + EGRU415 HMP FRANKLAND/LOW NEWTON + 544839N 0013233W -
544800N 0013221W -
544753N 0013317W -
544810N 0013351W -
544832N 0013351W -
544839N 0013233W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 208 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5424833333,54.81091944439999,213.36 -1.5641277778,54.8088,213.36 -1.564175,54.8027777778,213.36 -1.5547861111,54.7981777778,213.36 -1.5392111111,54.8001333333,213.36 -1.5424833333,54.81091944439999,213.36 + + + + +
+ + EGRU416 HMP HOLME HOUSE + 543500N 0011748W -
543500N 0011715W -
543433N 0011658W -
543422N 0011718W -
543423N 0011748W -
543435N 0011809W -
543448N 0011809W -
543500N 0011748W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 39 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2967611111,54.5833138889,152.4 -1.302475,54.5800361111,152.4 -1.3024944444,54.5763805556,152.4 -1.2966055556,54.57292222219999,152.4 -1.2882555556,54.5729055556,152.4 -1.2827388889,54.57594722220001,152.4 -1.2874805556,54.58325,152.4 -1.2967611111,54.5833138889,152.4 + + + + +
+ + EGRU417 HMP LANCASTER FARMS + 540337N 0024623W -
540334N 0024557W -
540325N 0024544W -
540304N 0024548W -
540255N 0024607W -
540256N 0024629W -
540309N 0024645W -
540329N 0024641W -
540337N 0024623W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 238 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7730277778,54.0601888889,213.36 -2.7780666667,54.058,213.36 -2.7792722222,54.0525166667,213.36 -2.7747222222,54.0490194444,213.36 -2.7687166667,54.0486583333,213.36 -2.7634277778,54.0510416667,213.36 -2.7621972222,54.0569194444,213.36 -2.7657555556,54.0595777778,213.36 -2.7730277778,54.0601888889,213.36 + + + + +
+ + EGRU501A LONDONDERRY/EGLINTON + A circle, 2.5 NM radius, centred at 550234N 0070943W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.1619444444,55.084367829,609.6 -7.16863411,55.0841902302,609.6 -7.1752665251,55.08365895349999,609.6 -7.1817849341,55.0827785455,609.6 -7.1881335654,55.08155654,609.6 -7.1942581135,55.0800033933,609.6 -7.2001062067,55.0781323936,609.6 -7.205627858,55.0759595465,609.6 -7.2107758951,55.0735034372,609.6 -7.2155063643,55.07078507,609.6 -7.219778907500001,55.0678276874,609.6 -7.2235571058,55.06465657050001,609.6 -7.2268087892,55.0612988211,609.6 -7.2295063091,55.0577831292,609.6 -7.2316267707,55.05413952659999,609.6 -7.2331522246,55.0503991296,609.6 -7.234069814599999,55.0465938723,609.6 -7.2343718823,55.0427562335,609.6 -7.2340560266,55.038918959,609.6 -7.233125118200001,55.0351147825,609.6 -7.2315872689,55.0313761459,609.6 -7.229455757,55.0277349233,609.6 -7.2267489084,55.0242221499,609.6 -7.2234899355,55.0208677583,609.6 -7.2197067351,55.0177003241,609.6 -7.215431647400001,55.0147468236,609.6 -7.210701178200001,55.0120324057,609.6 -7.2055556855,55.00958017850001,609.6 -7.2000390363,55.00741101410001,609.6 -7.1941982326,55.0055433721,609.6 -7.188083013200001,55.00399314400001,609.6 -7.1817454321,55.0027735185,609.6 -7.1752394186,55.0018948709,609.6 -7.1686203219,55.001364675,609.6 -7.1619444444,55.00118744049999,609.6 -7.1552685669,55.001364675,609.6 -7.1486494703,55.0018948709,609.6 -7.1421434567,55.0027735185,609.6 -7.135805875599999,55.00399314400001,609.6 -7.1296906563,55.0055433721,609.6 -7.1238498526,55.00741101410001,609.6 -7.118333203400001,55.00958017850001,609.6 -7.1131877107,55.0120324057,609.6 -7.108457241399999,55.0147468236,609.6 -7.1041821538,55.0177003241,609.6 -7.1003989534,55.0208677583,609.6 -7.0971399805,55.0242221499,609.6 -7.0944331319,55.0277349233,609.6 -7.09230162,55.0313761459,609.6 -7.090763770699999,55.0351147825,609.6 -7.0898328623,55.038918959,609.6 -7.0895170066,55.0427562335,609.6 -7.089819074300001,55.0465938723,609.6 -7.0907366643,55.0503991296,609.6 -7.0922621182,55.05413952659999,609.6 -7.0943825798,55.0577831292,609.6 -7.0970800997,55.0612988211,609.6 -7.1003317831,55.06465657050001,609.6 -7.104109981399999,55.0678276874,609.6 -7.1083825246,55.07078507,609.6 -7.1131129938,55.0735034372,609.6 -7.1182610309,55.0759595465,609.6 -7.1237826822,55.0781323936,609.6 -7.1296307754,55.0800033933,609.6 -7.1357553235,55.08155654,609.6 -7.1421039548,55.0827785455,609.6 -7.1486223637,55.08365895349999,609.6 -7.1552547789,55.0841902302,609.6 -7.1619444444,55.084367829,609.6 + + + + +
+ + EGRU501B LONDONDERRY/EGLINTON RWY 08 + 550123N 0071453W -
550154N 0071509W -
550206N 0071359W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to
550135N 0071343W -
550123N 0071453W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.2479777778,55.0229694444,609.6 -7.2284896389,55.02637775,609.6 -7.2303766768,55.02917460599999,609.6 -7.2319081121,55.0320422966,609.6 -7.233075916700001,55.0349659167,609.6 -7.2525111111,55.0315666667,609.6 -7.2479777778,55.0229694444,609.6 + + + + +
+ + EGRU501C LONDONDERRY/EGLINTON RWY 26 + 550345N 0070429W -
550314N 0070412W -
550301N 0070527W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to
550332N 0070543W -
550345N 0070429W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.074627777799999,55.06254166670001,609.6 -7.0952194167,55.0589717778,609.6 -7.0933618418,55.05616776699999,609.6 -7.091861437,55.0532941684,609.6 -7.090725944399999,55.05036594439999,609.6 -7.070083333300001,55.0539444444,609.6 -7.074627777799999,55.06254166670001,609.6 + + + + +
+ + EGRU502A ISLAY + A circle, 2 NM radius, centred at 554100N 0061535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.259722222200001,55.7166018889,609.6 -6.265781982300001,55.71642541239999,609.6 -6.271777344999999,55.7158978586,609.6 -6.2776446024,55.7150248334,609.6 -6.2833214183,55.71381561379999,609.6 -6.288747494299999,55.712283048,609.6 -6.2938652149,55.7104434183,609.6 -6.298620262100001,55.70831626660001,609.6 -6.3029621938,55.705924186,609.6 -6.3068449806,55.7032925788,609.6 -6.3102274936,55.70044938560001,609.6 -6.313073939,55.6974247876,609.6 -6.315354235199999,55.6942508839,609.6 -6.317044327400001,55.69096135070001,609.6 -6.318126438,55.6875910823,609.6 -6.3185892489,55.68417582049999,609.6 -6.318428015199999,55.68075177480001,609.6 -6.3176446087,55.6773552385,609.6 -6.316247491,55.674022204,609.6 -6.3142516173,55.6707879818,609.6 -6.311678271700001,55.6676868271,609.6 -6.3085548363,55.6647515777,609.6 -6.3049144963,55.66201330769999,609.6 -6.3007958855,55.6595009996,609.6 -6.296242674400001,55.6572412388,609.6 -6.291303106999999,55.65525793430001,609.6 -6.2860294903,55.65357206640001,609.6 -6.2804776422,55.6522014666,609.6 -6.2747063031,55.65116063029999,609.6 -6.2687765182,55.65046056400001,609.6 -6.2627509957,55.6501086704,609.6 -6.2566934487,55.6501086704,609.6 -6.2506679263,55.65046056400001,609.6 -6.2447381414,55.65116063029999,609.6 -6.2389668023,55.6522014666,609.6 -6.2334149541,55.65357206640001,609.6 -6.228141337499999,55.65525793430001,609.6 -6.22320177,55.6572412388,609.6 -6.2186485589,55.6595009996,609.6 -6.2145299481,55.66201330769999,609.6 -6.2108896082,55.6647515777,609.6 -6.2077661728,55.6676868271,609.6 -6.2051928272,55.6707879818,609.6 -6.2031969535,55.674022204,609.6 -6.201799835800001,55.6773552385,609.6 -6.201016429199999,55.68075177480001,609.6 -6.200855195599999,55.68417582049999,609.6 -6.201318006500001,55.6875910823,609.6 -6.202400117000001,55.69096135070001,609.6 -6.204090209199999,55.6942508839,609.6 -6.2063705054,55.6974247876,609.6 -6.2092169508,55.70044938560001,609.6 -6.212599463800001,55.7032925788,609.6 -6.216482250700001,55.705924186,609.6 -6.2208241824,55.70831626660001,609.6 -6.2255792295,55.7104434183,609.6 -6.2306969501,55.712283048,609.6 -6.2361230262,55.71381561379999,609.6 -6.241799842,55.7150248334,609.6 -6.247667099499999,55.7158978586,609.6 -6.2536624622,55.71642541239999,609.6 -6.259722222200001,55.7166018889,609.6 + + + + +
+ + EGRU502B ISLAY RWY 07 + 553948N 0061952W -
554018N 0062011W -
554032N 0061901W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554002N 0061840W -
553948N 0061952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3310583333,55.66321111109999,609.6 -6.3112065278,55.6671968889,609.6 -6.3135733497,55.6698858046,609.6 -6.3155017861,55.6726843614,609.6 -6.316976027799999,55.6755697778,609.6 -6.3363611111,55.6716777778,609.6 -6.3310583333,55.66321111109999,609.6 + + + + +
+ + EGRU502C ISLAY RWY 25 + 554212N 0061040W -
554142N 0061021W -
554121N 0061206W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554152N 0061224W -
554212N 0061040W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.1778694444,55.70338611110001,609.6 -6.20656975,55.69766322220001,609.6 -6.2045004609,55.6948971441,609.6 -6.202881467100001,55.6920369256,609.6 -6.2017258611,55.6891058889,609.6 -6.1725583333,55.6949222222,609.6 -6.1778694444,55.70338611110001,609.6 + + + + +
+ + EGRU502D ISLAY RWY 12 + 554220N 0062026W -
554248N 0061957W -
554215N 0061820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554147N 0061850W -
554220N 0062026W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3406861111,55.7055111111,609.6 -6.3138358611,55.69646419439999,609.6 -6.3115212547,55.69916690559999,609.6 -6.3087842929,55.7017407062,609.6 -6.3056472222,55.7041646111,609.6 -6.3325194444,55.7132194444,609.6 -6.3406861111,55.7055111111,609.6 + + + + +
+ + EGRU502E ISLAY RWY 30 + 553941N 0061044W -
553913N 0061113W -
553945N 0061249W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554013N 0061220W -
553941N 0061044W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.1788166667,55.6612916667,609.6 -6.2055239444,55.6703383333,609.6 -6.2078192916,55.66763068100001,609.6 -6.210536853499999,55.66505095510001,609.6 -6.2136544444,55.6626201389,609.6 -6.186966666699999,55.6535805556,609.6 -6.1788166667,55.6612916667,609.6 + + + + +
+ + EGRU503A CAMPBELTOWN + A circle, 2 NM radius, centred at 552615N 0054117W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6881,55.4708865645,609.6 -5.6941220147,55.4707100823,609.6 -5.7000800346,55.4701825112,609.6 -5.705910750200001,55.46930945730001,609.6 -5.711552214399999,55.4681001977,609.6 -5.716944505800001,55.4665675807,609.6 -5.7220303684,55.4647278888,609.6 -5.7267558229,55.46260066430001,609.6 -5.7310707415,55.46020850039999,609.6 -5.7349293813,55.4575768001,609.6 -5.7382908687,55.4547335046,609.6 -5.7411196321,55.4517087954,609.6 -5.743385775599999,55.44853477299999,609.6 -5.745065392900001,55.4452451142,609.6 -5.7461408152,55.4418747144,609.6 -5.746600793000001,55.4384593168,609.6 -5.746440609,55.43503513219999,609.6 -5.7456621213,55.4316384554,609.6 -5.744273737,55.4283052805,609.6 -5.7422903165,55.4250709195,609.6 -5.73973301,55.4219696294,609.6 -5.7366290279,55.4190342499,609.6 -5.733011348100001,55.4162958566,609.6 -5.728918363500001,55.4137834338,609.6 -5.7243934726,55.41152356869999,609.6 -5.719484619799999,55.4095401715,609.6 -5.714243787199999,55.4078542242,609.6 -5.7087264464,55.4064835594,609.6 -5.7029909739,55.40544267330001,609.6 -5.6970980365,55.4047425735,609.6 -5.6911099543,55.404390663,609.6 -5.6850900457,55.404390663,609.6 -5.6791019635,55.4047425735,609.6 -5.673209026100001,55.40544267330001,609.6 -5.6674735536,55.4064835594,609.6 -5.661956212799999,55.4078542242,609.6 -5.656715380200001,55.4095401715,609.6 -5.6518065274,55.41152356869999,609.6 -5.647281636499999,55.4137834338,609.6 -5.643188651899999,55.4162958566,609.6 -5.6395709721,55.4190342499,609.6 -5.63646699,55.4219696294,609.6 -5.633909683500001,55.4250709195,609.6 -5.631926263,55.4283052805,609.6 -5.6305378787,55.4316384554,609.6 -5.629759391,55.43503513219999,609.6 -5.629599206999999,55.4384593168,609.6 -5.6300591848,55.4418747144,609.6 -5.631134607099999,55.4452451142,609.6 -5.632814224400001,55.44853477299999,609.6 -5.6350803679,55.4517087954,609.6 -5.6379091313,55.4547335046,609.6 -5.6412706187,55.4575768001,609.6 -5.6451292585,55.46020850039999,609.6 -5.6494441771,55.46260066430001,609.6 -5.6541696316,55.4647278888,609.6 -5.6592554942,55.4665675807,609.6 -5.664647785599999,55.4681001977,609.6 -5.6702892498,55.46930945730001,609.6 -5.6761199654,55.4701825112,609.6 -5.6820779853,55.4707100823,609.6 -5.6881,55.4708865645,609.6 + + + + +
+ + EGRU503B CAMPBELTOWN RWY 11 + 552646N 0054608W -
552717N 0054552W -
552704N 0054430W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to
552633N 0054446W -
552646N 0054608W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7688818889,55.4461494167,609.6 -5.74600975,55.4424185278,609.6 -5.745014558799999,55.4453669439,609.6 -5.7435556738,55.4482523464,609.6 -5.7416448611,55.4510512222,609.6 -5.764505805600001,55.4547803611,609.6 -5.7688818889,55.4461494167,609.6 + + + + +
+ + EGRU503C CAMPBELTOWN RWY 29 + 552535N 0053529W -
552504N 0053544W -
552527N 0053804W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to
552558N 0053749W -
552535N 0053529W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5912708611,55.4263978889,609.6 -5.630200833300001,55.4328010278,609.6 -5.631202123399999,55.4298533037,609.6 -5.6326664256,55.42696888670001,609.6 -5.634581749999999,55.42417125000001,609.6 -5.5956437778,55.4177668889,609.6 -5.5912708611,55.4263978889,609.6 + + + + +
+ + EGRU504A PRESTWICK + A circle, 2.5 NM radius, centred at 553034N 0043540W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5945805556,55.5509785198,609.6 -4.6013492444,55.55080093139999,609.6 -4.6080600036,55.550269686,609.6 -4.6146554036,55.54938933010001,609.6 -4.6210790116,55.5481673976,609.6 -4.6272758781,55.54661434449999,609.6 -4.6331930109,55.5447434589,609.6 -4.6387798314,55.5425707464,609.6 -4.6439886091,55.5401147917,609.6 -4.6487748714,55.5373965986,609.6 -4.6530977841,55.5344394092,609.6 -4.6569204995,55.5312685036,609.6 -4.6602104698,55.5279109828,609.6 -4.6629397226,55.5243955356,609.6 -4.6650850957,55.5207521923,609.6 -4.6666284315,55.51701206749999,609.6 -4.6675567258,55.5132070933,609.6 -4.6678622339,55.5093697465,609.6 -4.6675425307,55.50553277060001,609.6 -4.6666005248,55.50172889629999,609.6 -4.6650444277,55.4979905628,609.6 -4.6628876781,55.49434964139999,609.6 -4.6601488213,55.4908371641,609.6 -4.6568513462,55.4874830602,609.6 -4.6530234809,55.48431590209999,609.6 -4.6486979487,55.4813626631,609.6 -4.6439116863,55.4786484888,609.6 -4.6387055281,55.47619648450001,609.6 -4.6331238575,55.4740275195,609.6 -4.6272142294,55.4721600508,609.6 -4.621026967,55.47060996769999,609.6 -4.6146147355,55.469390457,609.6 -4.6080320968,55.4685118925,609.6 -4.6013350494,55.4679817469,609.6 -4.5945805556,55.4678045293,609.6 -4.5878260617,55.4679817469,609.6 -4.5811290143,55.4685118925,609.6 -4.5745463757,55.469390457,609.6 -4.5681341441,55.47060996769999,609.6 -4.5619468817,55.4721600508,609.6 -4.5560372536,55.4740275195,609.6 -4.550455583,55.47619648450001,609.6 -4.5452494248,55.4786484888,609.6 -4.5404631624,55.4813626631,609.6 -4.5361376302,55.48431590209999,609.6 -4.5323097649,55.4874830602,609.6 -4.5290122898,55.4908371641,609.6 -4.526273433,55.49434964139999,609.6 -4.5241166834,55.4979905628,609.6 -4.5225605863,55.50172889629999,609.6 -4.5216185804,55.50553277060001,609.6 -4.5212988772,55.5093697465,609.6 -4.5216043854,55.5132070933,609.6 -4.5225326796,55.51701206749999,609.6 -4.5240760154,55.5207521923,609.6 -4.5262213885,55.5243955356,609.6 -4.5289506413,55.5279109828,609.6 -4.5322406116,55.5312685036,609.6 -4.536063327,55.5344394092,609.6 -4.5403862397,55.5373965986,609.6 -4.545172502,55.5401147917,609.6 -4.5503812797,55.5425707464,609.6 -4.5559681002,55.5447434589,609.6 -4.561885233,55.54661434449999,609.6 -4.5680820995,55.5481673976,609.6 -4.5745057075,55.54938933010001,609.6 -4.5811011075,55.550269686,609.6 -4.5878118667,55.55080093139999,609.6 -4.5945805556,55.5509785198,609.6 + + + + +
+ + EGRU504B PRESTWICK RWY 02 + 552644N 0043643W -
552657N 0043735W -
552808N 0043640W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
552804N 0043541W -
552644N 0043643W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6119638889,55.44545555559999,609.6 -4.5946817778,55.4678045556,609.6 -4.6002036153,55.467927257,609.6 -4.605693511,55.4682859911,609.6 -4.6111202778,55.46887872220001,609.6 -4.6264277778,55.4490722222,609.6 -4.6119638889,55.44545555559999,609.6 + + + + +
+ + EGRU504C PRESTWICK RWY 20 + 553247N 0043304W -
553234N 0043212W -
553215N 0043226W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
553237N 0043311W -
553247N 0043304W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.551125,55.5462972222,609.6 -4.5531429722,55.5436986389,609.6 -4.548697861,55.5418268629,609.6 -4.5445148706,55.539770143,609.6 -4.5406178611,55.5375402222,609.6 -4.5366222222,55.5426833333,609.6 -4.551125,55.5462972222,609.6 + + + + +
+ + EGRU504D PRESTWICK RWY 12 + 553205N 0044100W -
553233N 0044030W -
553205N 0043910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
553137N 0043939W -
553205N 0044100W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6832444444,55.534725,609.6 -4.6609490833,55.5270424444,609.6 -4.6585352738,55.5297116791,609.6 -4.655788149,55.5322752062,609.6 -4.6527219722,55.5347196667,609.6 -4.675,55.5423972222,609.6 -4.6832444444,55.534725,609.6 + + + + +
+ + EGRU504E PRESTWICK RWY 30 + 552858N 0043010W -
552831N 0043040W -
552903N 0043211W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
552930N 0043142W -
552858N 0043010W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5027611111,55.4828555556,609.6 -4.528274,55.4917018333,609.6 -4.5306940537,55.48903589719999,609.6 -4.5334458761,55.4864758646,609.6 -4.5365151111,55.4840350278,609.6 -4.5109833333,55.4751833333,609.6 -4.5027611111,55.4828555556,609.6 + + + + +
+ + EGRU505A GLASGOW + A circle, 2.5 NM radius, centred at 555218N 0042601W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4336611111,55.9133066058,609.6 -4.4404927814,55.9131290254,609.6 -4.4472659805,55.9125978039,609.6 -4.4539227421,55.911717488,609.6 -4.4604061061,55.9104956113,609.6 -4.4666606098,55.90894262999999,609.6 -4.4726327666,55.907071832,609.6 -4.4782715259,55.9048992227,609.6 -4.4835287129,55.90244338659999,609.6 -4.4883594411,55.8997253273,609.6 -4.4927224969,55.8967682863,609.6 -4.4965806909,55.8935975433,609.6 -4.4999011742,55.8902401984,609.6 -4.5026557162,55.88672493950001,609.6 -4.5048209421,55.883081796,609.6 -4.5063785279,55.8793418811,609.6 -4.5073153518,55.8755371254,609.6 -4.5076236004,55.8717000041,609.6 -4.5073008292,55.8678632586,609.6 -4.5063499773,55.8640596179,609.6 -4.5047793358,55.86032151889999,609.6 -4.502602471,55.8566808305,609.6 -4.4998381033,55.8531685823,609.6 -4.496509942,55.8498147012,609.6 -4.4926464793,55.846647757,609.6 -4.4882807436,55.8436947207,609.6 -4.4834500153,55.8409807353,609.6 -4.4781955083,55.8385289038,609.6 -4.4725620176,55.8363600934,609.6 -4.4665975388,55.83449275910001,609.6 -4.4603528607,55.8329427885,609.6 -4.4538811356,55.8317233669,609.6 -4.4472374298,55.83084486689999,609.6 -4.4404782588,55.8303147604,609.6 -4.4336611111,55.83013755579999,609.6 -4.4268439634,55.8303147604,609.6 -4.4200847924,55.83084486689999,609.6 -4.4134410866,55.8317233669,609.6 -4.4069693615,55.8329427885,609.6 -4.4007246835,55.83449275910001,609.6 -4.3947602046,55.8363600934,609.6 -4.3891267139,55.8385289038,609.6 -4.3838722069,55.8409807353,609.6 -4.3790414787,55.8436947207,609.6 -4.3746757429,55.846647757,609.6 -4.3708122802,55.8498147012,609.6 -4.367484119,55.8531685823,609.6 -4.3647197512,55.8566808305,609.6 -4.3625428864,55.86032151889999,609.6 -4.3609722449,55.8640596179,609.6 -4.360021393,55.8678632586,609.6 -4.3596986219,55.8717000041,609.6 -4.3600068705,55.8755371254,609.6 -4.3609436943,55.8793418811,609.6 -4.3625012801,55.883081796,609.6 -4.364666506,55.88672493950001,609.6 -4.367421048,55.8902401984,609.6 -4.3707415313,55.8935975433,609.6 -4.3745997254,55.8967682863,609.6 -4.3789627812,55.8997253273,609.6 -4.3837935094,55.90244338659999,609.6 -4.3890506963,55.9048992227,609.6 -4.3946894557,55.907071832,609.6 -4.4006616124,55.90894262999999,609.6 -4.4069161161,55.9104956113,609.6 -4.4133994801,55.911717488,609.6 -4.4200562418,55.9125978039,609.6 -4.4268294408,55.9131290254,609.6 -4.4336611111,55.9133066058,609.6 + + + + +
+ + EGRU505B GLASGOW RWY 05 + 554945N 0043005W -
555009N 0043044W -
555047N 0042933W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to
555024N 0042853W -
554945N 0043005W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5013388889,55.8292444444,609.6 -4.4813740556,55.8399566111,609.6 -4.4853205407,55.8419728253,609.6 -4.4889988796,55.844143751,609.6 -4.4923899444,55.8464581111,609.6 -4.5123388889,55.8357527778,609.6 -4.5013388889,55.8292444444,609.6 + + + + +
+ + EGRU505C GLASGOW RWY 23 + 555444N 0042210W -
555421N 0042130W -
555349N 0042229W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to
555412N 0042309W -
555444N 0042210W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3693777778,55.9122694444,609.6 -4.3858671944,55.9034677222,609.6 -4.3819197029,55.9014481405,609.6 -4.3782420207,55.8992738431,609.6 -4.3748532778,55.89695616669999,609.6 -4.35835,55.90576388889999,609.6 -4.3693777778,55.9122694444,609.6 + + + + +
+ + EGRU506A CUMBERNAULD + A circle, 2 NM radius, centred at 555829N 0035832W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9754333333,56.00792252559999,609.6 -3.9815386102,56.00774605590001,609.6 -3.9875790042,56.0072185223,609.6 -3.9934903273,56.0063455309,609.6 -3.9992097732,56.00513635829999,609.6 -4.0046765897,56.00360385279999,609.6 -4.0098327274,56.0017642963,609.6 -4.0146234598,55.9996372304,609.6 -4.0189979659,55.9972452479,609.6 -4.0229098711,55.9946137503,609.6 -4.026317738,55.991770678,609.6 -4.0291855056,55.9887462108,609.6 -4.0314828677,55.98557244730001,609.6 -4.0331855908,55.9822830623,609.6 -4.0342757661,55.978912949,609.6 -4.0347419927,55.9754978476,609.6 -4.0345794927,55.9720739659,609.6 -4.0337901541,55.9686775956,609.6 -4.0323825044,55.9653447272,609.6 -4.0303716132,55.9621106691,609.6 -4.0277789261,55.9590096745,609.6 -4.0246320321,55.9560745792,609.6 -4.0209643667,55.95333645500001,609.6 -4.0168148538,55.9508242826,609.6 -4.012227492,55.9485646454,609.6 -4.0072508868,55.94658145049999,609.6 -4.0019377369,55.9448956766,609.6 -3.9963442776,55.94352515389999,609.6 -3.9905296883,55.9424843764,609.6 -3.9845554704,55.94178434989999,609.6 -3.9784848002,55.9414324764,609.6 -3.9723818665,55.9414324764,609.6 -3.9663111963,55.94178434989999,609.6 -3.9603369783,55.9424843764,609.6 -3.9545223891,55.94352515389999,609.6 -3.9489289298,55.9448956766,609.6 -3.9436157799,55.94658145049999,609.6 -3.9386391747,55.9485646454,609.6 -3.9340518128,55.9508242826,609.6 -3.9299023,55.95333645500001,609.6 -3.9262346345,55.9560745792,609.6 -3.9230877405,55.9590096745,609.6 -3.9204950535,55.9621106691,609.6 -3.9184841622,55.9653447272,609.6 -3.9170765126,55.9686775956,609.6 -3.916287174,55.9720739659,609.6 -3.9161246739,55.9754978476,609.6 -3.9165909006,55.978912949,609.6 -3.9176810758,55.9822830623,609.6 -3.919383798999999,55.98557244730001,609.6 -3.9216811611,55.9887462108,609.6 -3.9245489286,55.991770678,609.6 -3.9279567956,55.9946137503,609.6 -3.9318687007,55.9972452479,609.6 -3.9362432069,55.9996372304,609.6 -3.9410339393,56.0017642963,609.6 -3.946190077,56.00360385279999,609.6 -3.9516568934,56.00513635829999,609.6 -3.957376339400001,56.0063455309,609.6 -3.9632876624,56.0072185223,609.6 -3.9693280564,56.00774605590001,609.6 -3.9754333333,56.00792252559999,609.6 + + + + +
+ + EGRU506B CUMBERNAULD RWY 07 + 555721N 0040320W -
555752N 0040338W -
555809N 0040202W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to
555738N 0040145W -
555721N 0040320W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0556527778,55.9557666667,609.6 -4.0290868333,55.96047041670001,609.6 -4.031149962,55.9632401287,609.6 -4.0327598646,55.9661028542,609.6 -4.0339033333,55.9690353056,609.6 -4.0604583333,55.9643333333,609.6 -4.0556527778,55.9557666667,609.6 + + + + +
+ + EGRU506C CUMBERNAULD RWY 25 + 555937N 0035343W -
555906N 0035325W -
555849N 0035501W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to
555920N 0035518W -
555937N 0035343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.895152777799999,55.9934916667,609.6 -3.9217423611,55.9888194444,609.6 -3.9196852867,55.9860479238,609.6 -3.9180825215,55.9831837186,609.6 -3.9169470278,55.9802501667,609.6 -3.8903416667,55.98492499999999,609.6 -3.895152777799999,55.9934916667,609.6 + + + + +
+ + EGRU507A EDINBURGH + A circle, 2.5 NM radius, centred at 555700N 0032221W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3725,55.9915838517,609.6 -3.3793454676,55.991406273,609.6 -3.3861323453,55.9908750567,609.6 -3.392802549399999,55.9899947493,609.6 -3.399299004,55.9887728846,609.6 -3.4055661343,55.9872199186,609.6 -3.411550345,55.9853491394,609.6 -3.4172004825,55.9831765523,609.6 -3.4224682743,55.9807207417,609.6 -3.4273087435,55.9780027111,609.6 -3.431680593199999,55.975045702,609.6 -3.4355465594,55.97187499390001,609.6 -3.438873727,55.9685176868,609.6 -3.4416338089,55.9650024685,609.6 -3.4438033837,55.9613593679,609.6 -3.445364091,55.95761949809999,609.6 -3.4463027832,55.9538147896,609.6 -3.446611632,55.9499777168,609.6 -3.4462881886,55.946141021,609.6 -3.4453353986,55.94233743060001,609.6 -3.4437615707,55.93859938209999,609.6 -3.4415802993,55.9349587439,609.6 -3.4388103428,55.9314465451,609.6 -3.4354754592,55.9280927121,609.6 -3.4316041982,55.92492581409999,609.6 -3.4272296552,55.9219728214,609.6 -3.422389186,55.91925887679999,609.6 -3.4171240874,55.91680708269999,609.6 -3.4114792447,55.9146383056,609.6 -3.40550275,55.9127710004,609.6 -3.3992454943,55.91122105409999,609.6 -3.3927607363,55.9100016517,609.6 -3.3861036529,55.9091231656,609.6 -3.379330872899999,55.9085930675,609.6 -3.3725,55.9084158658,609.6 -3.3656691271,55.9085930675,609.6 -3.3588963471,55.9091231656,609.6 -3.3522392637,55.9100016517,609.6 -3.3457545057,55.91122105409999,609.6 -3.33949725,55.9127710004,609.6 -3.3335207553,55.9146383056,609.6 -3.3278759126,55.91680708269999,609.6 -3.322610814,55.91925887679999,609.6 -3.3177703448,55.9219728214,609.6 -3.3133958018,55.92492581409999,609.6 -3.3095245408,55.9280927121,609.6 -3.3061896572,55.9314465451,609.6 -3.3034197007,55.9349587439,609.6 -3.3012384293,55.93859938209999,609.6 -3.2996646014,55.94233743060001,609.6 -3.2987118114,55.946141021,609.6 -3.298388368,55.9499777168,609.6 -3.2986972168,55.9538147896,609.6 -3.299635909,55.95761949809999,609.6 -3.3011966163,55.9613593679,609.6 -3.303366191099999,55.9650024685,609.6 -3.306126273,55.9685176868,609.6 -3.3094534406,55.97187499390001,609.6 -3.3133194068,55.975045702,609.6 -3.317691256499999,55.9780027111,609.6 -3.3225317257,55.9807207417,609.6 -3.3277995175,55.9831765523,609.6 -3.333449655,55.9853491394,609.6 -3.339433865699999,55.9872199186,609.6 -3.345700996,55.9887728846,609.6 -3.3521974506,55.9899947493,609.6 -3.3588676547,55.9908750567,609.6 -3.365654532399999,55.991406273,609.6 -3.3725,55.9915838517,609.6 + + + + +
+ + EGRU507B EDINBURGH RWY 06 + 555504N 0032705W -
555532N 0032735W -
555557N 0032623W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to
555529N 0032553W -
555504N 0032705W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4515083333,55.9179055556,609.6 -3.4313687778,55.9247520556,609.6 -3.4344587671,55.9271983849,609.6 -3.4372270503,55.92976332560001,609.6 -3.4396591944,55.9324335556,609.6 -3.459775,55.92559444439999,609.6 -3.4515083333,55.9179055556,609.6 + + + + +
+ + EGRU507C EDINBURGH RWY 24 + 555855N 0031737W -
555827N 0031707W -
555803N 0031819W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to
555831N 0031849W -
555855N 0031737W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2935388889,55.9819416667,609.6 -3.3135155278,55.97519091669999,609.6 -3.3104327879,55.9727397804,609.6 -3.307673542299999,55.970170342,609.6 -3.3052520833,55.967496,609.6 -3.2852555556,55.97425277779999,609.6 -3.2935388889,55.9819416667,609.6 + + + + +
+ + EGRU508A NEWCASTLE + A circle, 2.5 NM radius, centred at 550217N 0014123W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6898111111,55.07951230690001,609.6 -1.6964999664,55.0793347079,609.6 -1.7031315782,55.0788034309,609.6 -1.7096491977,55.0779230223,609.6 -1.7159970603,55.0767010161,609.6 -1.7221208669,55.0751478684,609.6 -1.7279682522,55.0732768675,609.6 -1.7334892353,55.071104019,609.6 -1.7386366495,55.0686479081,609.6 -1.7433665467,55.065929539,609.6 -1.7476385734,55.0629721544,609.6 -1.7514163152,55.0598010353,609.6 -1.754667606,55.0564432835,609.6 -1.7573648005,55.05292758910001,609.6 -1.7594850068,55.0492839838,609.6 -1.7610102773,55.0455435839,609.6 -1.7619277575,55.0417383236,609.6 -1.7622297899,55.0379006818,609.6 -1.7619139737,55.0340634042,609.6 -1.760983179,55.0302592245,609.6 -1.7594455168,55.0265205847,609.6 -1.7573142637,55.02287935900001,609.6 -1.7546077433,55.01936658260001,609.6 -1.7513491651,55.016012188,609.6 -1.7475664227,55.01284475080001,609.6 -1.7432918523,55.0098912476,609.6 -1.7385619551,55.00717682720001,609.6 -1.7334170845,55.0047245977,609.6 -1.727901102,55.0025554312,609.6 -1.7220610041,55.0006877874,609.6 -1.7159465234,54.9991375578,609.6 -1.7096097077,54.9979179311,609.6 -1.7031044799,54.9970392826,609.6 -1.6964861825,54.99650908620001,609.6 -1.6898111111,54.9963318516,609.6 -1.6831360397,54.99650908620001,609.6 -1.6765177423,54.9970392826,609.6 -1.6700125145,54.9979179311,609.6 -1.6636756989,54.9991375578,609.6 -1.6575612182,55.0006877874,609.6 -1.6517211202,55.0025554312,609.6 -1.6462051377,55.0047245977,609.6 -1.6410602671,55.00717682720001,609.6 -1.6363303699,55.0098912476,609.6 -1.6320557995,55.01284475080001,609.6 -1.6282730571,55.016012188,609.6 -1.6250144789,55.01936658260001,609.6 -1.6223079585,55.02287935900001,609.6 -1.6201767054,55.0265205847,609.6 -1.6186390432,55.0302592245,609.6 -1.6177082486,55.0340634042,609.6 -1.6173924323,55.0379006818,609.6 -1.6176944647,55.0417383236,609.6 -1.6186119449,55.0455435839,609.6 -1.6201372155,55.0492839838,609.6 -1.6222574217,55.05292758910001,609.6 -1.6249546162,55.0564432835,609.6 -1.628205907,55.0598010353,609.6 -1.6319836488,55.0629721544,609.6 -1.6362556755,55.065929539,609.6 -1.6409855727,55.0686479081,609.6 -1.6461329869,55.071104019,609.6 -1.6516539701,55.0732768675,609.6 -1.6575013554,55.0751478684,609.6 -1.6636251619,55.0767010161,609.6 -1.6699730245,55.0779230223,609.6 -1.676490644,55.0788034309,609.6 -1.6831222558,55.0793347079,609.6 -1.6898111111,55.07951230690001,609.6 + + + + +
+ + EGRU508B NEWCASTLE RWY 07 + 550040N 0014620W -
550109N 0014644W -
550129N 0014530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to
550059N 0014507W -
550040N 0014620W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7723027778,55.0110388889,609.6 -1.7518513611,55.0164843056,609.6 -1.7543812399,55.0191080779,609.6 -1.7565757289,55.0218297539,609.6 -1.7584233611,55.0246351944,609.6 -1.7788555556,55.0191944444,609.6 -1.7723027778,55.0110388889,609.6 + + + + +
+ + EGRU508C NEWCASTLE RWY 25 + 550353N 0013627W -
550324N 0013603W -
550304N 0013716W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to
550334N 0013740W -
550353N 0013627W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6074555556,55.0646833333,609.6 -1.6277036667,55.0593275,609.6 -1.6251793523,55.0567007126,609.6 -1.622991767,55.05397627000001,609.6 -1.62115225,55.0511683611,609.6 -1.6008888889,55.05652777779999,609.6 -1.6074555556,55.0646833333,609.6 + + + + +
+ + EGRU509A KIRKNEWTON + A circle, 2 NM radius, centred at 555224N 0032355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.398525,55.906473077,609.6 -3.4046143306,55.90629660500001,609.6 -3.4106389485,55.9057690643,609.6 -3.4165348337,55.9048960612,609.6 -3.4222393447,55.9036868723,609.6 -3.4276918883,55.9021543458,609.6 -3.4328345671,55.9003147639,609.6 -3.4376127976,55.8981876682,609.6 -3.4419758918,55.8957956516,609.6 -3.4458775957,55.8931641159,609.6 -3.449276580399999,55.8903210016,609.6 -3.452136878000001,55.8872964889,609.6 -3.4544282614,55.8841226767,609.6 -3.456126559499999,55.8808332402,609.6 -3.4572139095,55.877463073,609.6 -3.4576789395,55.87404791580001,609.6 -3.4575168832,55.8706239771,609.6 -3.4567296229,55.867227549,609.6 -3.4553256631,55.8638946228,609.6 -3.4533200331,55.8606605077,609.6 -3.450734122,55.8575594574,609.6 -3.4475954465,55.8546243084,609.6 -3.4439373541,55.8518861335,609.6 -3.4397986674,55.8493739138,609.6 -3.4352232698,55.84711423360001,609.6 -3.4302596402,55.84513100060001,609.6 -3.424960340200001,55.843445194,609.6 -3.4193814587,55.84207464439999,609.6 -3.4135820215,55.8410338464,609.6 -3.40762337,55.84033380610001,609.6 -3.4015685166,55.83998192559999,609.6 -3.3954814834,55.83998192559999,609.6 -3.38942663,55.84033380610001,609.6 -3.3834679785,55.8410338464,609.6 -3.3776685413,55.84207464439999,609.6 -3.372089659799999,55.843445194,609.6 -3.3667903598,55.84513100060001,609.6 -3.3618267302,55.84711423360001,609.6 -3.3572513326,55.8493739138,609.6 -3.3531126459,55.8518861335,609.6 -3.3494545535,55.8546243084,609.6 -3.346315878,55.8575594574,609.6 -3.3437299669,55.8606605077,609.6 -3.3417243369,55.8638946228,609.6 -3.3403203771,55.867227549,609.6 -3.3395331168,55.8706239771,609.6 -3.3393710605,55.87404791580001,609.6 -3.3398360905,55.877463073,609.6 -3.3409234405,55.8808332402,609.6 -3.3426217386,55.8841226767,609.6 -3.344913122,55.8872964889,609.6 -3.3477734196,55.8903210016,609.6 -3.3511724043,55.8931641159,609.6 -3.3550741082,55.8957956516,609.6 -3.3594372024,55.8981876682,609.6 -3.3642154329,55.9003147639,609.6 -3.3693581117,55.9021543458,609.6 -3.3748106553,55.9036868723,609.6 -3.3805151663,55.9048960612,609.6 -3.386411051500001,55.9057690643,609.6 -3.3924356694,55.90629660500001,609.6 -3.398525,55.906473077,609.6 + + + + +
+ + EGRU510 HMP NORTHUMBERLAND + 551818N 0013757W -
551756N 0013719W -
551743N 0013716W -
551716N 0013805W -
551720N 0013839W -
551737N 0013910W -
551818N 0013757W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 118 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6326027778,55.3049305556,182.88 -1.6528194444,55.2935,182.88 -1.6441694444,55.2888166667,182.88 -1.63475,55.2877805556,182.88 -1.6210055556,55.2953416667,182.88 -1.6220055556,55.2989555556,182.88 -1.6326027778,55.3049305556,182.88 + + + + +
+ + EGRU601A TIREE + A circle, 2 NM radius, centred at 562957N 0065209W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.8691666667,56.53243079859999,609.6 -6.8753560547,56.5322543409,609.6 -6.8814796627,56.5317268434,609.6 -6.8874724149,56.5308539119,609.6 -6.893270637199999,56.52964482310001,609.6 -6.898812738,56.5281124248,609.6 -6.9040398665,56.52627299859999,609.6 -6.9088965412,56.5241460857,609.6 -6.9133312409,56.5217542778,609.6 -6.917296952700001,56.5191229759,609.6 -6.92075167,56.5162801189,609.6 -6.9236588372,56.5132558855,609.6 -6.9259877337,56.5100823723,609.6 -6.9277137958,56.50679325229999,609.6 -6.928818872,56.5034234163,609.6 -6.9292914089,56.5000086018,609.6 -6.929126567,56.4965850139,609.6 -6.9283262651,56.4931889409,609.6 -6.926899152099999,56.4898563701,609.6 -6.9248605091,56.4866226063,609.6 -6.922232080200001,56.4835218989,609.6 -6.9190418369,56.4805870799,609.6 -6.9153236767,56.4778492177,609.6 -6.9111170607,56.47533728890001,609.6 -6.906466592800001,56.4730778737,609.6 -6.901421547,56.4710948757,609.6 -6.8960353454,56.46940927090001,609.6 -6.890364994899999,56.4680388867,609.6 -6.884470486200001,56.466998215,609.6 -6.8784141631,56.46629826,609.6 -6.8722600672,56.4659464225,609.6 -6.8660732661,56.4659464225,609.6 -6.8599191702,56.46629826,609.6 -6.8538628471,56.466998215,609.6 -6.8479683384,56.4680388867,609.6 -6.842297987900001,56.46940927090001,609.6 -6.836911786400001,56.4710948757,609.6 -6.8318667405,56.4730778737,609.6 -6.827216272600001,56.47533728890001,609.6 -6.823009656600001,56.4778492177,609.6 -6.8192914965,56.4805870799,609.6 -6.8161012532,56.4835218989,609.6 -6.8134728243,56.4866226063,609.6 -6.8114341812,56.4898563701,609.6 -6.8100070682,56.4931889409,609.6 -6.809206766299999,56.4965850139,609.6 -6.8090419244,56.5000086018,609.6 -6.8095144613,56.5034234163,609.6 -6.8106195375,56.50679325229999,609.6 -6.8123455996,56.5100823723,609.6 -6.814674496100001,56.5132558855,609.6 -6.8175816633,56.5162801189,609.6 -6.821036380700001,56.5191229759,609.6 -6.8250020924,56.5217542778,609.6 -6.829436792200001,56.5241460857,609.6 -6.8342934669,56.52627299859999,609.6 -6.8395205953,56.5281124248,609.6 -6.8450626961,56.52964482310001,609.6 -6.8508609184,56.5308539119,609.6 -6.8568536707,56.5317268434,609.6 -6.862977278600001,56.5322543409,609.6 -6.8691666667,56.53243079859999,609.6 + + + + +
+ + EGRU601B TIREE RWY 05 + 562739N 0065554W -
562803N 0065634W -
562848N 0065506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
562824N 0065426W -
562739N 0065554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.9317583333,56.4608361111,609.6 -6.9072867778,56.47344325,609.6 -6.9113222392,56.4754483478,609.6 -6.915015145399999,56.477646477,609.6 -6.9183354167,56.4800197778,609.6 -6.9428,56.4674138889,609.6 -6.9317583333,56.4608361111,609.6 + + + + +
+ + EGRU601C TIREE RWY 23 + 563213N 0064828W -
563149N 0064748W -
563106N 0064912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
563130N 0064952W -
563213N 0064828W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.807697222199999,56.5368638889,609.6 -6.831034250000001,56.5248960833,609.6 -6.8269941803,56.5228900067,609.6 -6.8232981894,56.5206906729,609.6 -6.8199763611,56.5183160278,609.6 -6.7966305556,56.5302861111,609.6 -6.807697222199999,56.5368638889,609.6 + + + + +
+ + EGRU601D TIREE RWY 11 + 563040N 0065734W -
563111N 0065716W -
563051N 0065522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
563021N 0065541W -
563040N 0065734W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.959330555599999,56.5110166667,609.6 -6.9281294444,56.5057391389,609.6 -6.9268188412,56.50865455729999,609.6 -6.925037655700001,56.5114926778,609.6 -6.922800333299999,56.51423033329999,609.6 -6.954561111099999,56.51960277780001,609.6 -6.959330555599999,56.5110166667,609.6 + + + + +
+ + EGRU601E TIREE RWY 29 + 562928N 0064712W -
562857N 0064730W -
562911N 0064849W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
562942N 0064834W -
562928N 0064712W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.7867861111,56.4911138889,609.6 -6.809503250000001,56.4949871389,609.6 -6.8104304407,56.4920271763,609.6 -6.8118364249,56.4891255438,609.6 -6.813709611100001,56.4863058889,609.6 -6.79155,56.4825277778,609.6 -6.7867861111,56.4911138889,609.6 + + + + +
+ + EGRU602A COLL + A circle, 2 NM radius, centred at 563607N 0063704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.6177444444,56.6353302443,609.6 -6.6239506685,56.635153789,609.6 -6.6300909328,56.6346262985,609.6 -6.6360999842,56.63375337869999,609.6 -6.6419139746,56.6325443062,609.6 -6.6474711444,56.6310119287,609.6 -6.6527124825,56.6291725279,609.6 -6.657582356300001,56.6270456447,609.6 -6.6620291044,56.62465387080001,609.6 -6.666005586100001,56.622022607,609.6 -6.6694696809,56.61917979190001,609.6 -6.6723847342,56.61615560399999,609.6 -6.6747199424,56.6129821396,609.6 -6.6764506758,56.60969307130001,609.6 -6.677558734399999,56.6063232894,609.6 -6.678032533999999,56.6029085309,609.6 -6.677867223200001,56.5994850003,609.6 -6.677064726499999,56.59608898550001,609.6 -6.6756337175,56.59275647279999,609.6 -6.6735895195,56.5895227666,609.6 -6.6709539363,56.5864221154,609.6 -6.667755016099999,56.5834873505,609.6 -6.6640267488,56.5807495395,609.6 -6.659808703,56.5782376584,609.6 -6.6551456038,56.5759782867,609.6 -6.650086859,56.5739953273,609.6 -6.6446860355,56.5723097556,609.6 -6.6390002947,56.57093939850001,609.6 -6.633089789499999,56.56989874749999,609.6 -6.6270170324,56.5691988065,609.6 -6.6208462383,56.5688469761,609.6 -6.6146426506,56.5688469761,609.6 -6.608471856499999,56.5691988065,609.6 -6.6023990994,56.56989874749999,609.6 -6.5964885942,56.57093939850001,609.6 -6.5908028534,56.5723097556,609.6 -6.5854020299,56.5739953273,609.6 -6.580343285100001,56.5759782867,609.6 -6.5756801859,56.5782376584,609.6 -6.5714621401,56.5807495395,609.6 -6.567733872799999,56.5834873505,609.6 -6.564534952600001,56.5864221154,609.6 -6.561899369399999,56.5895227666,609.6 -6.5598551714,56.59275647279999,609.6 -6.5584241624,56.59608898550001,609.6 -6.5576216657,56.5994850003,609.6 -6.557456354899999,56.6029085309,609.6 -6.5579301545,56.6063232894,609.6 -6.559038213000001,56.60969307130001,609.6 -6.560768946499999,56.6129821396,609.6 -6.563104154700001,56.61615560399999,609.6 -6.566019208,56.61917979190001,609.6 -6.5694833028,56.622022607,609.6 -6.5734597845,56.62465387080001,609.6 -6.5779065326,56.6270456447,609.6 -6.5827764064,56.6291725279,609.6 -6.588017744500001,56.6310119287,609.6 -6.5935749143,56.6325443062,609.6 -6.5993889047,56.63375337869999,609.6 -6.6053979561,56.6346262985,609.6 -6.6115382204,56.635153789,609.6 -6.6177444444,56.6353302443,609.6 + + + + +
+ + EGRU603A COLONSAY + A circle, 2 NM radius, centred at 560327N 0061435W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2430777778,56.0908304089,609.6 -6.2491961631,56.0906539411,609.6 -6.2552495257,56.0901264132,609.6 -6.2611735392,56.0892534313,609.6 -6.266905262099999,56.08804427210001,609.6 -6.2723838114,56.0865117836,609.6 -6.2775510128,56.0846722478,609.6 -6.2823520222,56.08254520639999,609.6 -6.286735909399999,56.08015325149999,609.6 -6.2906562002,56.07752178509999,609.6 -6.2940713687,56.0746787469,609.6 -6.2969452767,56.07165431689999,609.6 -6.299247553499999,56.06848059310001,609.6 -6.3009539141,56.0651912502,609.6 -6.302046411800001,56.0618211809,609.6 -6.302513622,56.058406125,609.6 -6.3023507571,56.0549822899,609.6 -6.301559710099999,56.05158596670001,609.6 -6.3001490272,56.0482531455,609.6 -6.2981338111,56.045019134,609.6 -6.295535553800001,56.0419181849,609.6 -6.2923819039,56.0389831333,609.6 -6.288706369,56.0362450506,609.6 -6.2845479568,56.0337329167,609.6 -6.279950759999999,56.03147331469999,609.6 -6.274963488399999,56.029490151,609.6 -6.2696389535,56.0278044039,609.6 -6.264033510699999,56.0264339031,609.6 -6.2582064661,56.0253931423,609.6 -6.252219452,56.0246931271,609.6 -6.24613578,56.02434125929999,609.6 -6.240019775500001,56.02434125929999,609.6 -6.2339361035,56.0246931271,609.6 -6.2279490895,56.0253931423,609.6 -6.222122044900001,56.0264339031,609.6 -6.2165166021,56.0278044039,609.6 -6.2111920672,56.029490151,609.6 -6.206204795600001,56.03147331469999,609.6 -6.2016075988,56.0337329167,609.6 -6.197449186499999,56.0362450506,609.6 -6.1937736516,56.0389831333,609.6 -6.190620001799999,56.0419181849,609.6 -6.1880217445,56.045019134,609.6 -6.1860065283,56.0482531455,609.6 -6.1845958455,56.05158596670001,609.6 -6.1838047984,56.0549822899,609.6 -6.1836419335,56.058406125,609.6 -6.184109143800001,56.0618211809,609.6 -6.1852016415,56.0651912502,609.6 -6.1869080021,56.06848059310001,609.6 -6.1892102788,56.07165431689999,609.6 -6.1920841868,56.0746787469,609.6 -6.1954993554,56.07752178509999,609.6 -6.1994196462,56.08015325149999,609.6 -6.2038035334,56.08254520639999,609.6 -6.2086045427,56.0846722478,609.6 -6.2137717441,56.0865117836,609.6 -6.2192502934,56.08804427210001,609.6 -6.224982016399999,56.0892534313,609.6 -6.230906029899999,56.0901264132,609.6 -6.2369593925,56.0906539411,609.6 -6.2430777778,56.0908304089,609.6 + + + + +
+ + EGRU604A OBAN + A circle, 2 NM radius, centred at 562749N 0052400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3998638889,56.4969837675,609.6 -5.406047503,56.49680730899999,609.6 -5.4121653987,56.4962798091,609.6 -5.4181525612,56.4954068736,609.6 -5.4239453758,56.4941977792,609.6 -5.4294823086,56.49266537370001,609.6 -5.4347045639,56.4908259387,609.6 -5.439556712,56.4886990155,609.6 -5.4439872797,56.4863071959,609.6 -5.4479492979,56.4836758809,609.6 -5.4514007993,56.48083300939999,609.6 -5.4543052619,56.4778087602,609.6 -5.4566319937,56.4746352302,609.6 -5.4583564538,56.4713460924,609.6 -5.4594605072,56.4679762377,609.6 -5.459932611,56.4645614039,609.6 -5.45976793,56.46113779620001,609.6 -5.4589683807,56.45774170319999,609.6 -5.4575426038,56.45440911229999,609.6 -5.4555058658,56.4511753287,609.6 -5.4528798905,56.4480746019,609.6 -5.4496926229,56.44513976439999,609.6 -5.445977929,56.4424018844,609.6 -5.4417752329,56.4398899392,609.6 -5.4371290969,56.43763050900001,609.6 -5.4320887491,56.4356474978,609.6 -5.4267075622,56.4339618815,609.6 -5.4210424898,56.432591488,609.6 -5.4151534672,56.43155080910001,609.6 -5.4091027801,56.43085084929999,609.6 -5.4029544109,56.4304990094,609.6 -5.3967733668,56.4304990094,609.6 -5.3906249977,56.43085084929999,609.6 -5.3845743106,56.43155080910001,609.6 -5.3786852879,56.432591488,609.6 -5.3730202156,56.4339618815,609.6 -5.3676390286,56.4356474978,609.6 -5.3625986809,56.43763050900001,609.6 -5.3579525449,56.4398899392,609.6 -5.3537498487,56.4424018844,609.6 -5.3500351548,56.44513976439999,609.6 -5.3468478873,56.4480746019,609.6 -5.3442219119,56.4511753287,609.6 -5.342185174,56.45440911229999,609.6 -5.3407593971,56.45774170319999,609.6 -5.3399598478,56.46113779620001,609.6 -5.3397951668,56.4645614039,609.6 -5.3402672706,56.4679762377,609.6 -5.341371324,56.4713460924,609.6 -5.3430957841,56.4746352302,609.6 -5.3454225159,56.4778087602,609.6 -5.3483269785,56.48083300939999,609.6 -5.3517784799,56.4836758809,609.6 -5.3557404981,56.4863071959,609.6 -5.3601710658,56.4886990155,609.6 -5.3650232139,56.4908259387,609.6 -5.3702454692,56.49266537370001,609.6 -5.375782402,56.4941977792,609.6 -5.3815752166,56.4954068736,609.6 -5.3875623791,56.4962798091,609.6 -5.3936802747,56.49680730899999,609.6 -5.3998638889,56.4969837675,609.6 + + + + +
+ + EGRU604B OBAN RWY 01 + 562451N 0052402W -
562454N 0052500W -
562553N 0052449W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to
562550N 0052351W -
562451N 0052402W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.4004833333,56.4140361111,609.6 -5.3975838056,56.4304789167,609.6 -5.4030012099,56.4305003651,609.6 -5.4083931319,56.4307920761,609.6 -5.4137157778,56.4313516944,609.6 -5.4166083333,56.4149083333,609.6 -5.4004833333,56.4140361111,609.6 + + + + +
+ + EGRU604C OBAN RWY 19 + 563046N 0052358W -
563043N 0052300W -
562946N 0052310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to
562949N 0052408W -
563046N 0052358W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3993666667,56.5127111111,609.6 -5.4021495278,56.4969597222,609.6 -5.3967225023,56.49693832589999,609.6 -5.3913211261,56.4966461693,609.6 -5.3859895,56.49608563889999,609.6 -5.3832,56.51183611110001,609.6 -5.3993666667,56.5127111111,609.6 + + + + +
+ + EGRU605A PERTH/SCONE + A circle, 2 NM radius, centred at 562628N 0032226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3739055556,56.4743894449,609.6 -3.3800854962,56.4742129859,609.6 -3.3861997576,56.47368548440001,609.6 -3.3921833637,56.4728125464,609.6 -3.3979727379,56.4716034484,609.6 -3.4035063827,56.47007103829999,609.6 -3.4087255376,56.4682315978,609.6 -3.413574805700001,56.466104668,609.6 -3.4180027446,56.4637128409,609.6 -3.4219624129,56.46108151749999,609.6 -3.4254118681,56.4582386368,609.6 -3.428314610000001,56.45521437759999,609.6 -3.4306399647,56.4520408369,609.6 -3.4323634055,56.4487516877,609.6 -3.4334668082,56.44538182109999,609.6 -3.4339386364,56.44196697489999,609.6 -3.4337740577,56.43854335459999,609.6 -3.4329749872,56.43514724890001,609.6 -3.4315500604,56.43181464519999,609.6 -3.4295145345,56.4285808489,609.6 -3.4268901202,56.42548010980001,609.6 -3.4237047459,56.4225452604,609.6 -3.4199922572,56.4198073692,609.6 -3.415792055,56.4172954134,609.6 -3.4111486751,56.4150359737,609.6 -3.4061113164,56.413052954,609.6 -3.4007333198,56.41136733050001,609.6 -3.3950716055,56.409996931,609.6 -3.3891860732,56.4089562476,609.6 -3.383138971899999,56.4082562846,609.6 -3.3769942462,56.4079044432,609.6 -3.3708168649,56.4079044432,609.6 -3.3646721392,56.4082562846,609.6 -3.3586250379,56.4089562476,609.6 -3.3527395056,56.409996931,609.6 -3.3470777913,56.41136733050001,609.6 -3.341699794699999,56.413052954,609.6 -3.336662436,56.4150359737,609.6 -3.3320190561,56.4172954134,609.6 -3.3278188539,56.4198073692,609.6 -3.3241063652,56.4225452604,609.6 -3.3209209909,56.42548010980001,609.6 -3.318296576599999,56.4285808489,609.6 -3.316261050700001,56.43181464519999,609.6 -3.3148361239,56.43514724890001,609.6 -3.3140370534,56.43854335459999,609.6 -3.3138724747,56.44196697489999,609.6 -3.314344303,56.44538182109999,609.6 -3.3154477056,56.4487516877,609.6 -3.3171711464,56.4520408369,609.6 -3.3194965011,56.45521437759999,609.6 -3.322399243,56.4582386368,609.6 -3.325848698300001,56.46108151749999,609.6 -3.3298083665,56.4637128409,609.6 -3.3342363054,56.466104668,609.6 -3.3390855735,56.4682315978,609.6 -3.3443047284,56.47007103829999,609.6 -3.3498383732,56.4716034484,609.6 -3.3556277474,56.4728125464,609.6 -3.3616113535,56.47368548440001,609.6 -3.3677256149,56.4742129859,609.6 -3.3739055556,56.4743894449,609.6 + + + + +
+ + EGRU605B PERTH/SCONE RWY 03 + 562346N 0032431W -
562401N 0032522W -
562451N 0032433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562436N 0032342W -
562346N 0032431W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4084972222,56.39609166669999,609.6 -3.3949996667,56.4099819444,609.6 -3.3999783657,56.4111619804,609.6 -3.4047452434,56.4125858503,609.6 -3.4092615556,56.4142419722,609.6 -3.422750000000001,56.40035555560001,609.6 -3.4084972222,56.39609166669999,609.6 + + + + +
+ + EGRU605C PERTH/SCONE RWY 21 + 562910N 0032021W -
562855N 0031930W -
562805N 0032019W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562820N 0032110W -
562910N 0032021W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3392388889,56.4861444444,609.6 -3.3527793333,56.47226480560001,609.6 -3.3477937836,56.47108294669999,609.6 -3.3430213946,56.46965693160001,609.6 -3.3385010833,56.4679984167,609.6 -3.3249527778,56.4818805556,609.6 -3.3392388889,56.4861444444,609.6 + + + + +
+ + EGRU605D PERTH/SCONE RWY 09 + 562554N 0032720W -
562627N 0032721W -
562628N 0032602W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562556N 0032554W -
562554N 0032720W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4554361111,56.4317694444,609.6 -3.4317364167,56.43217586109999,609.6 -3.4329649966,56.4351170685,609.6 -3.4337073317,56.4381078709,609.6 -3.4339572222,56.4411236389,609.6 -3.4559194444,56.4407472222,609.6 -3.4554361111,56.4317694444,609.6 + + + + +
+ + EGRU605E PERTH/SCONE RWY 27 + 562637N 0031711W -
562604N 0031709W -
562603N 0031855W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562635N 0031850W -
562637N 0031711W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2863305556,56.4435527778,609.6 -3.3139595278,56.4431115278,609.6 -3.3138835923,56.4400935224,609.6 -3.3143017912,56.43708412620001,609.6 -3.3152105556,56.4341081111,609.6 -3.2858444444,56.4345777778,609.6 -3.2863305556,56.4435527778,609.6 + + + + +
+ + EGRU605F PERTH/SCONE RWY 15 + 562844N 0032509W -
562900N 0032418W -
562821N 0032337W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562806N 0032429W -
562844N 0032509W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.419075,56.47875,609.6 -3.408111277799999,56.4684703889,609.6 -3.4035104538,56.4700697543,609.6 -3.3986671264,56.4714324112,609.6 -3.3936209444,56.47254719439999,609.6 -3.4050944444,56.4833083333,609.6 -3.419075,56.47875,609.6 + + + + +
+ + EGRU605G PERTH/SCONE RWY 33 + 562404N 0031904W -
562348N 0031954W -
562441N 0032050W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562459N 0032002W -
562404N 0031904W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.317663888899999,56.401125,609.6 -3.3338338333,56.41635597220001,609.6 -3.3380343685,56.41445234959999,609.6 -3.3425274864,56.4127666313,609.6 -3.3472765278,56.4113125833,609.6 -3.3316138889,56.3965638889,609.6 -3.317663888899999,56.401125,609.6 + + + + +
+ + EGRU606A DUNDEE + A circle, 2 NM radius, centred at 562709N 0030133W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0258333333,56.4857643835,609.6 -3.0320151227,56.48558792480001,609.6 -3.0381312131,56.48506042409999,609.6 -3.044116609,56.4841874874,609.6 -3.0499077146,56.4829783912,609.6 -3.0554430142,56.48144598340001,609.6 -3.0606637293,56.47960654569999,609.6 -3.0655144468,56.4774796192,609.6 -3.0699437087,56.4750877959,609.6 -3.0739045596,56.4724564767,609.6 -3.0773550446,56.4696136006,609.6 -3.0802586524,56.4665893465,609.6 -3.0825847002,56.4634158112,609.6 -3.084308654,56.4601266677,609.6 -3.085412384100001,56.4567568071,609.6 -3.085884351,56.45334196709999,609.6 -3.0857197208,56.4499183532,609.6 -3.0849204094,56.4465222539,609.6 -3.083495054800001,56.4431896566,609.6 -3.0814589189,56.4399558667,609.6 -3.078833719,56.4368551338,609.6 -3.0756473919,56.43392029030001,609.6 -3.0719337934,56.4311824048,609.6 -3.067732336,56.42867045439999,609.6 -3.0630875691,56.4264110194,609.6 -3.0580487061,56.424428004,609.6 -3.052669104,56.4227423841,609.6 -3.0470056997,56.4213719876,609.6 -3.0411184109,56.4203313065,609.6 -3.035069505,56.41963134520001,609.6 -3.0289229457,56.41927950449999,609.6 -3.022743721,56.41927950449999,609.6 -3.0165971617,56.41963134520001,609.6 -3.0105482558,56.4203313065,609.6 -3.0046609669,56.4213719876,609.6 -2.998997562700001,56.4227423841,609.6 -2.9936179605,56.424428004,609.6 -2.9885790975,56.4264110194,609.6 -2.9839343306,56.42867045439999,609.6 -2.9797328733,56.4311824048,609.6 -2.9760192748,56.43392029030001,609.6 -2.9728329477,56.4368551338,609.6 -2.9702077478,56.4399558667,609.6 -2.9681716119,56.4431896566,609.6 -2.9667462573,56.4465222539,609.6 -2.9659469459,56.4499183532,609.6 -2.9657823156,56.45334196709999,609.6 -2.9662542826,56.4567568071,609.6 -2.9673580127,56.4601266677,609.6 -2.9690819665,56.4634158112,609.6 -2.9714080142,56.4665893465,609.6 -2.9743116221,56.4696136006,609.6 -2.9777621071,56.4724564767,609.6 -2.981722958000001,56.4750877959,609.6 -2.9861522199,56.4774796192,609.6 -2.9910029373,56.47960654569999,609.6 -2.9962236525,56.48144598340001,609.6 -3.001758951999999,56.4829783912,609.6 -3.0075500577,56.4841874874,609.6 -3.0135354536,56.48506042409999,609.6 -3.0196515439,56.48558792480001,609.6 -3.0258333333,56.4857643835,609.6 + + + + +
+ + EGRU606B DUNDEE RWY 09 + 562654N 0030706W -
562726N 0030705W -
562726N 0030507W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to
562654N 0030507W -
562654N 0030706W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1183416667,56.44835,609.6 -3.0853967222,56.4482048333,609.6 -3.0858557268,56.4511958568,609.6 -3.0858259999,56.4541976161,609.6 -3.0853076667,56.4571856667,609.6 -3.1181916667,56.4573305556,609.6 -3.1183416667,56.44835,609.6 + + + + +
+ + EGRU606C DUNDEE RWY 27 + 562723N 0025600W -
562651N 0025600W -
562651N 0025759W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to
562724N 0025758W -
562723N 0025600W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9333166667,56.4564027778,609.6 -2.9662158889,56.4565880278,609.6 -2.9657954518,56.45359527630001,609.6 -2.9658639633,56.45059372160001,609.6 -2.966420750000001,56.4476078056,609.6 -2.9334611111,56.4474222222,609.6 -2.9333166667,56.4564027778,609.6 + + + + +
+ + EGRU607A LEUCHARS + A circle, 2.5 NM radius, centred at 562230N 0025132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8587805556,56.41647264160001,609.6 -2.8657021278,56.4162950721,609.6 -2.8725644557,56.4157638834,609.6 -2.879308806800001,56.41488362209999,609.6 -2.8858774683,56.4136618219,609.6 -2.892214244899999,56.4121089388,609.6 -2.8982649438,56.4102382607,609.6 -2.9039778414,56.4080657928,609.6 -2.9093041281,56.4056101194,609.6 -2.914198326699999,56.4028922436,609.6 -2.9186186821,56.39993540649999,609.6 -2.9225275174,56.39676488679999,609.6 -2.925891553600001,56.39340778380001,609.6 -2.928682191900001,56.3898927841,609.6 -2.9308757535,56.3862499157,609.6 -2.9324536776,56.38251029,609.6 -2.9334026742,56.37870583559999,609.6 -2.9337148321,56.3748690254,609.6 -2.9333876794,56.3710325982,609.6 -2.9324241985,56.3672292802,609.6 -2.9308327941,56.3634915053,609.6 -2.928627215100001,56.3598511391,609.6 -2.9258264316,56.356339208,609.6 -2.9224544677,56.35298563530001,609.6 -2.9185401925,56.34981898749999,609.6 -2.9141170699,56.3468662319,609.6 -2.9092228713,56.34415250829999,609.6 -2.9038993517,56.34170091650001,609.6 -2.8981918941,56.33953232050001,609.6 -2.892149122699999,56.3376651727,609.6 -2.8858224914,56.3361153582,609.6 -2.8792658473,56.3348960602,609.6 -2.8725349765,56.3340176497,609.6 -2.8656871329,56.3334875974,609.6 -2.8587805556,56.333310411,609.6 -2.8518739782,56.3334875974,609.6 -2.8450261346,56.3340176497,609.6 -2.8382952638,56.3348960602,609.6 -2.8317386198,56.3361153582,609.6 -2.8254119884,56.3376651727,609.6 -2.8193692171,56.33953232050001,609.6 -2.8136617594,56.34170091650001,609.6 -2.8083382398,56.34415250829999,609.6 -2.8034440412,56.3468662319,609.6 -2.7990209186,56.34981898749999,609.6 -2.7951066434,56.35298563530001,609.6 -2.7917346795,56.356339208,609.6 -2.788933896,56.3598511391,609.6 -2.786728317,56.3634915053,609.6 -2.7851369126,56.3672292802,609.6 -2.7841734317,56.3710325982,609.6 -2.783846279,56.3748690254,609.6 -2.7841584369,56.37870583559999,609.6 -2.7851074336,56.38251029,609.6 -2.7866853576,56.3862499157,609.6 -2.7888789192,56.3898927841,609.6 -2.7916695575,56.39340778380001,609.6 -2.7950335937,56.39676488679999,609.6 -2.798942429,56.39993540649999,609.6 -2.8033627844,56.4028922436,609.6 -2.808256983,56.4056101194,609.6 -2.8135832697,56.4080657928,609.6 -2.819296167300001,56.4102382607,609.6 -2.8253468662,56.4121089388,609.6 -2.8316836428,56.4136618219,609.6 -2.8382523043,56.41488362209999,609.6 -2.8449966554,56.4157638834,609.6 -2.8518589833,56.4162950721,609.6 -2.8587805556,56.41647264160001,609.6 + + + + +
+ + EGRU607B LEUCHARS RWY 04 + 561957N 0025452W -
562017N 0025539W -
562050N 0025453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562028N 0025410W -
561957N 0025452W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9144206944,56.3325690833,609.6 -2.9027777778,56.34124019439999,609.6 -2.9070505126,56.3430960833,609.6 -2.9110705021,56.3451187835,609.6 -2.9148166667,56.3472976944,609.6 -2.9273748889,56.33794275,609.6 -2.9144206944,56.3325690833,609.6 + + + + +
+ + EGRU607C LEUCHARS RWY 22 + 562509N 0024905W -
562449N 0024819W -
562428N 0024847W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562445N 0024937W -
562509N 0024905W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8181688333,56.41909744439999,609.6 -2.826999194399999,56.4125516667,609.6 -2.822164781200001,56.4111759222,609.6 -2.8175231097,56.4096095711,609.6 -2.8130985833,56.40786086109999,609.6 -2.8051870833,56.4137238333,609.6 -2.8181688333,56.41909744439999,609.6 + + + + +
+ + EGRU607D LEUCHARS RWY 08 + 562145N 0025723W -
562217N 0025731W -
562224N 0025601W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562152N 0025553W -
562145N 0025723W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9562513333,56.36250361110001,609.6 -2.9313368611,56.36452075,609.6 -2.9324977062,56.3674495154,609.6 -2.9332753622,56.37041709300001,609.6 -2.9336656944,56.37340805560001,609.6 -2.9585670556,56.3713919722,609.6 -2.9562513333,56.36250361110001,609.6 + + + + +
+ + EGRU607E LEUCHARS RWY 26 + 562314N 0024541W -
562242N 0024532W -
562235N 0024702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562307N 0024710W -
562314N 0024541W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7612772778,56.3872223611,609.6 -2.7861945833,56.38524102780001,609.6 -2.7850416753,56.3823112446,609.6 -2.7842725202,56.3793429756,609.6 -2.7838910278,56.3763516667,609.6 -2.7589605833,56.3783340278,609.6 -2.7612772778,56.3872223611,609.6 + + + + +
+ + EGRU701A BARRA + A circle, 2 NM radius, centred at 570122N 0072635W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.4430555556,57.0560390985,609.6 -7.4493317926,57.0558626526,609.6 -7.455541323000001,57.0553351905,609.6 -7.4616181547,57.05446231799999,609.6 -7.4674977172,57.0532533114,609.6 -7.473117551999999,57.0517210185,609.6 -7.478417981,57.0498817204,609.6 -7.4833427432,57.0477549579,609.6 -7.4878395942,57.045363322,609.6 -7.491860862,57.04273221289999,609.6 -7.495363952599999,57.0398895683,609.6 -7.4983117994,57.0368655654,609.6 -7.5006732542,57.0336922995,609.6 -7.502423412400001,57.0304034414,609.6 -7.503543871900001,57.0270338796,609.6 -7.5040229219,57.0236193492,609.6 -7.5038556597,57.0201960523,609.6 -7.5030440356,57.0168002742,609.6 -7.5015968243,57.01346799859999,609.6 -7.499529525,57.01023452690001,609.6 -7.4968641904,57.0071341048,609.6 -7.4936291869,57.0041995606,609.6 -7.489858889200001,57.0014619587,609.6 -7.4855933127,56.9989502723,609.6 -7.4808776867,56.996691078,609.6 -7.475761975199999,56.9947082762,609.6 -7.4703003474,56.99302283969999,609.6 -7.4645506066,56.9916525934,609.6 -7.4585735812,56.9906120271,609.6 -7.4524324849,56.9899121433,609.6 -7.4461922524,56.98956034169999,609.6 -7.4399188587,56.98956034169999,609.6 -7.4336786262,56.9899121433,609.6 -7.4275375299,56.9906120271,609.6 -7.4215605045,56.9916525934,609.6 -7.4158107637,56.99302283969999,609.6 -7.410349136000001,56.9947082762,609.6 -7.4052334244,56.996691078,609.6 -7.4005177984,56.9989502723,609.6 -7.396252221899999,57.0014619587,609.6 -7.3924819242,57.0041995606,609.6 -7.3892469207,57.0071341048,609.6 -7.3865815861,57.01023452690001,609.6 -7.3845142869,57.01346799859999,609.6 -7.3830670755,57.0168002742,609.6 -7.3822554514,57.0201960523,609.6 -7.3820881892,57.0236193492,609.6 -7.382567239199999,57.0270338796,609.6 -7.383687698699999,57.0304034414,609.6 -7.3854378569,57.0336922995,609.6 -7.3877993117,57.0368655654,609.6 -7.390747158500001,57.0398895683,609.6 -7.3942502491,57.04273221289999,609.6 -7.3982715169,57.045363322,609.6 -7.4027683679,57.0477549579,609.6 -7.4076931301,57.0498817204,609.6 -7.412993559100001,57.0517210185,609.6 -7.4186133939,57.0532533114,609.6 -7.4244929564,57.05446231799999,609.6 -7.430569788099999,57.0553351905,609.6 -7.4367793185,57.0558626526,609.6 -7.4430555556,57.0560390985,609.6 + + + + +
+ + EGRU701B BARRA RWY 07 + 570009N 0073107W -
570038N 0073131W -
570058N 0073010W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570027N 0072950W -
570009N 0073107W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.518661111100001,57.00238055560001,609.6 -7.4972838889,57.0075711389,609.6 -7.499584313799999,57.01030810419999,609.6 -7.5014219593,57.0131473248,609.6 -7.5027816667,57.0160655556,609.6 -7.5253361111,57.01058888890001,609.6 -7.518661111100001,57.00238055560001,609.6 + + + + +
+ + EGRU701C BARRA RWY 25 + 570300N 0072146W -
570230N 0072122W -
570204N 0072310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570233N 0072338W -
570300N 0072146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.362816666700001,57.049925,609.6 -7.39384875,57.04243672220001,609.6 -7.390790637700001,57.039929051,609.6 -7.3881615015,57.0372808229,609.6 -7.385982805600001,57.0345137778,609.6 -7.3561305556,57.0417166667,609.6 -7.362816666700001,57.049925,609.6 + + + + +
+ + EGRU701D BARRA RWY 11 + 570143N 0073151W -
570214N 0073140W -
570204N 0073000W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570133N 0073014W -
570143N 0073151W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.5307805556,57.0285111111,609.6 -7.5037998333,57.02575224999999,609.6 -7.5030623655,57.02872919030001,609.6 -7.501835202200001,57.0316576943,609.6 -7.50012825,57.0345138611,609.6 -7.5277277778,57.03733611109999,609.6 -7.5307805556,57.0285111111,609.6 + + + + +
+ + EGRU701E BARRA RWY 29 + 570111N 0072125W -
570039N 0072136W -
570049N 0072304W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570121N 0072255W -
570111N 0072125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.356827777800001,57.0197555556,609.6 -7.3820743056,57.0223684167,609.6 -7.382393158600001,57.0193695108,609.6 -7.383206654499999,57.0163985197,609.6 -7.3845080556,57.0134796667,609.6 -7.359877777800001,57.0109305556,609.6 -7.356827777800001,57.0197555556,609.6 + + + + +
+ + EGRU701F BARRA RWY 15 + 570324N 0073025W -
570345N 0072940W -
570303N 0072834W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570242N 0072919W -
570324N 0073025W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.506858333300001,57.0565277778,609.6 -7.4886011111,57.04490583329999,609.6 -7.4847575404,57.04705471100001,609.6 -7.4805738096,57.04900587710001,609.6 -7.476084,57.0507434167,609.6 -7.494330555599999,57.0623611111,609.6 -7.506858333300001,57.0565277778,609.6 + + + + +
+ + EGRU701G BARRA RWY 33 + 565921N 0072247W -
565900N 0072332W -
565941N 0072436W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570002N 0072351W -
565921N 0072247W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3795888889,56.98913888890001,609.6 -7.3975619444,57.0006344167,609.6 -7.401405478100001,56.9984881114,609.6 -7.4055874261,56.99653947529999,609.6 -7.410073749999999,56.9948043333,609.6 -7.3920916667,56.9833055556,609.6 -7.3795888889,56.98913888890001,609.6 + + + + +
+ + EGRU702A BENBECULA + A circle, 2 NM radius, centred at 572850N 0072150W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3638888889,57.5138144373,609.6 -7.370243523,57.5136380016,609.6 -7.376530614,57.51311056989999,609.6 -7.3826833427,57.512237748,609.6 -7.3886363291,57.5110288122,609.6 -7.3943263326,57.50949661,609.6 -7.3996929278,57.5076574223,609.6 -7.4046791501,57.5055307894,609.6 -7.4092321026,57.5031393019,609.6 -7.4133035183,57.5005083591,609.6 -7.4168502725,57.4976658978,609.6 -7.4198348381,57.49464209439999,609.6 -7.422225680400001,57.4914690423,609.6 -7.423997587400001,57.48818041100001,609.6 -7.4251319309,57.4848110868,609.6 -7.425616858000001,57.4813968027,609.6 -7.425447409,57.4779737584,609.6 -7.424625562800001,57.4745782363,609.6 -7.4231602077,57.47124621719999,609.6 -7.42106704,57.4680129995,609.6 -7.418368390800001,57.46491282560001,609.6 -7.415092983200001,57.4619785206,609.6 -7.4112756225,57.4592411455,609.6 -7.4069568246,57.4567296703,609.6 -7.4021823834,57.4544706685,609.6 -7.397002885499999,57.4524880377,609.6 -7.3914731746,57.450802748,609.6 -7.3856517729,57.4494326221,609.6 -7.3796002648,57.4483921478,609.6 -7.3733826489,57.4476923261,609.6 -7.3670646665,57.4473405559,609.6 -7.360713111299999,57.4473405559,609.6 -7.3543951289,57.4476923261,609.6 -7.348177513000001,57.4483921478,609.6 -7.3421260049,57.4494326221,609.6 -7.3363046032,57.450802748,609.6 -7.3307748923,57.4524880377,609.6 -7.3255953944,57.4544706685,609.6 -7.3208209532,57.4567296703,609.6 -7.3165021552,57.4592411455,609.6 -7.3126847946,57.4619785206,609.6 -7.3094093869,57.46491282560001,609.6 -7.3067107378,57.4680129995,609.6 -7.3046175701,57.47124621719999,609.6 -7.303152215,57.4745782363,609.6 -7.302330368699999,57.4779737584,609.6 -7.3021609198,57.4813968027,609.6 -7.302645846900001,57.4848110868,609.6 -7.3037801904,57.48818041100001,609.6 -7.3055520973,57.4914690423,609.6 -7.307942939700001,57.49464209439999,609.6 -7.3109275052,57.4976658978,609.6 -7.314474259499999,57.5005083591,609.6 -7.3185456752,57.5031393019,609.6 -7.3230986276,57.5055307894,609.6 -7.328084849999999,57.5076574223,609.6 -7.3334514452,57.50949661,609.6 -7.3391414487,57.5110288122,609.6 -7.345094435099999,57.512237748,609.6 -7.351247163800001,57.51311056989999,609.6 -7.357534254800001,57.5136380016,609.6 -7.3638888889,57.5138144373,609.6 + + + + +
+ + EGRU702B BENBECULA RWY 06 + 572652N 0072615W -
572719N 0072649W -
572756N 0072509W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
572730N 0072435W -
572652N 0072615W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.4375166667,57.4478472222,609.6 -7.4096192222,57.45821586110001,609.6 -7.413171273099999,57.46052727600001,609.6 -7.4163226737,57.46300177,609.6 -7.4190477222,57.4656192222,609.6 -7.4469583333,57.4552444444,609.6 -7.4375166667,57.4478472222,609.6 + + + + +
+ + EGRU702C BENBECULA RWY 24 + 573054N 0071710W -
573027N 0071636W -
572944N 0071832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
573011N 0071906W -
573054N 0071710W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.286077777799999,57.5148805556,609.6 -7.31827175,57.50297872219999,609.6 -7.3147038122,57.5006722278,609.6 -7.3115371197,57.4982018809,609.6 -7.308797416699999,57.4955878333,609.6 -7.2766166667,57.5074833333,609.6 -7.286077777799999,57.5148805556,609.6 + + + + +
+ + EGRU702D BENBECULA RWY 17 + 573147N 0072334W -
573154N 0072235W -
573049N 0072207W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
573043N 0072306W -
573147N 0072334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.392660055600001,57.52968433329999,609.6 -7.3849875,57.51181438890001,609.6 -7.379665191,57.5127115306,609.6 -7.3742140602,57.5133465673,609.6 -7.3686786111,57.5137143056,609.6 -7.3763938333,57.53170225,609.6 -7.392660055600001,57.52968433329999,609.6 + + + + +
+ + EGRU702E BENBECULA RWY 35 + 572601N 0072004W -
572554N 0072102W -
572651N 0072127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
572659N 0072028W -
572601N 0072004W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3344309722,57.4336456389,609.6 -7.3412491111,57.4496147778,609.6 -7.3465157972,57.44864127630001,609.6 -7.3519236088,57.4479274827,609.6 -7.3574286111,57.4474791944,609.6 -7.3506536944,57.4316276944,609.6 -7.3344309722,57.4336456389,609.6 + + + + +
+ + EGRU703A INVERNESS + A circle, 2.5 NM radius, centred at 573233N 0040251W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0475444444,57.5840676082,609.6 -4.0546862389,57.58389006329999,609.6 -4.0617668949,57.5833589483,609.6 -4.0687258029,57.5824788098,609.6 -4.0755034058,57.5812571816,609.6 -4.0820417136,57.5797045197,609.6 -4.088284804,57.577834112,609.6 -4.0941793039,57.5756619633,609.6 -4.0996748488,57.5732066576,609.6 -4.104724515,57.5704891971,609.6 -4.1092852208,57.56753282179999,609.6 -4.1133180947,57.564362809,609.6 -4.1167888052,57.5610062559,609.6 -4.1196678512,57.5574918464,609.6 -4.1219308101,57.55384960519999,609.6 -4.123558541,57.5501106398,609.6 -4.1245373428,57.5463068745,609.6 -4.1248590642,57.54247077670001,609.6 -4.1245211671,57.5386350794,609.6 -4.1235267406,57.53483250240001,609.6 -4.1218844678,57.53109547249999,609.6 -4.1196085452,57.527455848,609.6 -4.1167185551,57.5239446474,609.6 -4.1132392927,57.520591786,609.6 -4.1092005504,57.51742582220001,609.6 -4.1046368596,57.5144737151,609.6 -4.0995871934,57.5117605968,609.6 -4.0940946335,57.5093095592,609.6 -4.0882060019,57.5071414595,609.6 -4.0819714634,57.5052747435,609.6 -4.0754440997,57.50372529050001,609.6 -4.0686794606,57.50250627909999,609.6 -4.0617350944,57.501628076,609.6 -4.0546700632,57.5010981493,609.6 -4.0475444444,57.500921005,609.6 -4.0404188257,57.5010981493,609.6 -4.0333537944,57.501628076,609.6 -4.0264094283,57.50250627909999,609.6 -4.0196447892,57.50372529050001,609.6 -4.0131174255,57.5052747435,609.6 -4.006882887,57.5071414595,609.6 -4.0009942554,57.5093095592,609.6 -3.9955016955,57.5117605968,609.6 -3.9904520293,57.5144737151,609.6 -3.9858883385,57.51742582220001,609.6 -3.9818495962,57.520591786,609.6 -3.9783703338,57.5239446474,609.6 -3.9754803436,57.527455848,609.6 -3.9732044211,57.53109547249999,609.6 -3.971562148299999,57.53483250240001,609.6 -3.9705677217,57.5386350794,609.6 -3.9702298247,57.54247077670001,609.6 -3.9705515461,57.5463068745,609.6 -3.9715303479,57.5501106398,609.6 -3.9731580788,57.55384960519999,609.6 -3.9754210377,57.5574918464,609.6 -3.978300083700001,57.5610062559,609.6 -3.9817707942,57.564362809,609.6 -3.9858036681,57.56753282179999,609.6 -3.990364373899999,57.5704891971,609.6 -3.99541404,57.5732066576,609.6 -4.000909585,57.5756619633,609.6 -4.0068040849,57.577834112,609.6 -4.0130471752,57.5797045197,609.6 -4.0195854831,57.5812571816,609.6 -4.026363086,57.5824788098,609.6 -4.033321994,57.5833589483,609.6 -4.04040265,57.58389006329999,609.6 -4.0475444444,57.5840676082,609.6 + + + + +
+ + EGRU703B INVERNESS RWY 05 + 573017N 0040700W -
573042N 0040739W -
573108N 0040641W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573044N 0040602W -
573017N 0040700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1166388889,57.5047583333,609.6 -4.1004858611,57.51220786110001,609.6 -4.1044062774,57.5143384338,609.6 -4.1080315965,57.5166154193,609.6 -4.1113429444,57.51902700000001,609.6 -4.1274805556,57.5115833333,609.6 -4.1166388889,57.5047583333,609.6 + + + + +
+ + EGRU703C INVERNESS RWY 23 + 573450N 0035839W -
573426N 0035800W -
573357N 0035901W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573422N 0035940W -
573450N 0035839W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9774833333,57.580575,609.6 -3.9945199444,57.5727610833,609.6 -3.990598808,57.57062697550001,609.6 -3.9869746432,57.5683464492,609.6 -3.9836663056,57.5659313889,609.6 -3.9666166667,57.57375,609.6 -3.9774833333,57.580575,609.6 + + + + +
+ + EGRU703D INVERNESS RWY 11 + 573320N 0040829W -
573350N 0040809W -
573337N 0040702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573307N 0040722W -
573320N 0040829W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1413694444,57.5554416667,609.6 -4.1228588611,57.5519122778,609.6 -4.1214032257,57.55480654239999,609.6 -4.119563074,57.5576368626,609.6 -4.1173478889,57.5603885,609.6 -4.1357638889,57.5639,609.6 -4.1413694444,57.5554416667,609.6 + + + + +
+ + EGRU703E INVERNESS RWY 29 + 573154N 0035803W -
573124N 0035823W -
573127N 0035841W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573158N 0035821W -
573154N 0035803W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9673888889,57.5316694444,609.6 -3.9724428889,57.53264099999999,609.6 -3.9739612196,57.5297563839,609.6 -3.975861807899999,57.52693809669999,609.6 -3.9781346944,57.5242007778,609.6 -3.9729861111,57.5232111111,609.6 -3.9673888889,57.5316694444,609.6 + + + + +
+ + EGRU705A LOSSIEMOUTH + A circle, 2.5 NM radius, centred at 574224N 0032016W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3378888889,57.7482304105,609.6 -3.3450630202,57.7480528689,609.6 -3.352175735,57.747521764,609.6 -3.3591661478,57.7466416423,609.6 -3.365974431000001,57.74542003760001,609.6 -3.3725423308,57.74386740610001,609.6 -3.3788136709,57.7419970354,609.6 -3.3847348362,57.7398249306,609.6 -3.3902552337,57.7373696753,609.6 -3.3953277273,57.73465227200001,609.6 -3.3999090406,57.7316959604,609.6 -3.4039601267,57.72852601749999,609.6 -3.4074464995,57.7251695403,609.6 -3.410338525599999,57.7216552125,609.6 -3.4126116729,57.7180130581,609.6 -3.4142467157,57.71427418439999,609.6 -3.4152298924,57.7104705148,609.6 -3.4155530167,57.7066345159,609.6 -3.415213540499999,57.7027989203,609.6 -3.4142145688,57.6989964465,609.6 -3.4125648257,57.6952595206,609.6 -3.410278573399999,57.69161999969999,609.6 -3.4073754839,57.68810890110001,609.6 -3.4038804661,57.6847561392,609.6 -3.3998234477,57.6815902711,609.6 -3.3952391168,57.6786382549,609.6 -3.3901666232,57.6759252214,609.6 -3.3846492432,57.6734742616,609.6 -3.3787340102,57.6713062315,609.6 -3.3724713151,57.6694395761,609.6 -3.365914478600001,57.66789017390001,609.6 -3.3591193005,57.66667120260001,609.6 -3.352143588000001,57.66579302870001,609.6 -3.3450466683,57.66526311970001,609.6 -3.3378888889,57.66508598130001,609.6 -3.3307311095,57.66526311970001,609.6 -3.323634189799999,57.66579302870001,609.6 -3.3166584773,57.66667120260001,609.6 -3.309863299199999,57.66789017390001,609.6 -3.3033064627,57.6694395761,609.6 -3.2970437676,57.6713062315,609.6 -3.2911285346,57.6734742616,609.6 -3.2856111546,57.6759252214,609.6 -3.280538661,57.6786382549,609.6 -3.2759543301,57.6815902711,609.6 -3.2718973117,57.6847561392,609.6 -3.268402293899999,57.68810890110001,609.6 -3.265499204400001,57.69161999969999,609.6 -3.2632129521,57.6952595206,609.6 -3.261563209000001,57.6989964465,609.6 -3.2605642373,57.7027989203,609.6 -3.2602247611,57.7066345159,609.6 -3.2605478854,57.7104705148,609.6 -3.2615310621,57.71427418439999,609.6 -3.263166104899999,57.7180130581,609.6 -3.2654392522,57.7216552125,609.6 -3.2683312783,57.7251695403,609.6 -3.2718176511,57.72852601749999,609.6 -3.2758687372,57.7316959604,609.6 -3.2804500505,57.73465227200001,609.6 -3.285522544,57.7373696753,609.6 -3.2910429416,57.7398249306,609.6 -3.2969641068,57.7419970354,609.6 -3.303235447,57.74386740610001,609.6 -3.3098033468,57.74542003760001,609.6 -3.3166116299,57.7466416423,609.6 -3.3236020428,57.747521764,609.6 -3.3307147576,57.7480528689,609.6 -3.3378888889,57.7482304105,609.6 + + + + +
+ + EGRU705B LOSSIEMOUTH RWY 05 + 573945N 0032419W -
574007N 0032502W -
574048N 0032350W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574025N 0032307W -
573945N 0032419W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4052303889,57.66239622219999,609.6 -3.3851451111,57.6736762778,609.6 -3.3894605228,57.6755851141,609.6 -3.3935083929,57.67765548039999,609.6 -3.3972676667,57.6798766389,609.6 -3.4173429722,57.6686000833,609.6 -3.4052303889,57.66239622219999,609.6 + + + + +
+ + EGRU705C LOSSIEMOUTH RWY 23 + 574503N 0031614W -
574441N 0031530W -
574400N 0031642W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574423N 0031726W -
574503N 0031614W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2704251389,57.7508905278,609.6 -3.2905774444,57.7396351944,609.6 -3.2862578363,57.7377241466,609.6 -3.2822074459,57.7356514462,609.6 -3.2784473611,57.7334278889,609.6 -3.2582850556,57.74468675,609.6 -3.2704251389,57.7508905278,609.6 + + + + +
+ + EGRU705D LOSSIEMOUTH RWY 10 + 574228N 0032535W -
574300N 0032529W -
574258N 0032449W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574225N 0032456W -
574228N 0032535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.426483277800001,57.7077121111,609.6 -3.4155498889,57.7070576667,609.6 -3.4152973401,57.7100528307,609.6 -3.4146420388,57.7130304583,609.6 -3.4135873056,57.7159750556,609.6 -3.4245959444,57.716634,609.6 -3.426483277800001,57.7077121111,609.6 + + + + +
+ + EGRU705E LOSSIEMOUTH RWY 28 + 574217N 0031343W -
574145N 0031350W -
574152N 0031543W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574224N 0031537W -
574217N 0031343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2287245833,57.7047635833,609.6 -3.2602247222,57.70669352779999,609.6 -3.260425149,57.70369724730001,609.6 -3.2610283953,57.70071648859999,609.6 -3.2620312222,57.69776675,609.6 -3.2306113056,57.6958416944,609.6 -3.2287245833,57.7047635833,609.6 + + + + +
+ + EGRU706A ABERDEEN/DYCE + A circle, 2.5 NM radius, centred at 571209N 0021153W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1980555556,57.2440754236,609.6 -2.2051314822,57.2438978716,609.6 -2.2121468371,57.2433667355,609.6 -2.2190415719,57.24248656180001,609.6 -2.2257566814,57.2412648843,609.6 -2.2322347123,57.23971215899999,609.6 -2.2384202596,57.2378416738,609.6 -2.2442604437,57.2356694335,609.6 -2.249705365,57.23321402219999,609.6 -2.2547085326,57.2304964423,609.6 -2.2592272616,57.2275399342,609.6 -2.2632230376,57.22436977550001,609.6 -2.266661844,57.221013064,609.6 -2.2695144494,57.2174984844,609.6 -2.2717566538,57.2138560622,609.6 -2.2733694897,57.2101169061,609.6 -2.2743393788,57.2063129417,609.6 -2.2746582417,57.2024766378,609.6 -2.2743235599,57.1986407293,609.6 -2.2733383906,57.19483793769999,609.6 -2.2717113336,57.1911006919,609.6 -2.2694564514,57.18746085240001,609.6 -2.2665931431,57.18394943980001,609.6 -2.2631459735,57.180596372,609.6 -2.2591444585,57.1774302095,609.6 -2.2546228104,57.174477914,609.6 -2.2496196428,57.1717646198,609.6 -2.2441776406,57.1693134211,609.6 -2.2383431954,57.1671451771,609.6 -2.2321660113,57.1652783355,609.6 -2.2256986832,57.1637287773,609.6 -2.2189962516,57.1625096825,609.6 -2.2121157379,57.1616314191,609.6 -2.2051156633,57.1611014558,609.6 -2.1980555556,57.1609242992,609.6 -2.1909954478,57.1611014558,609.6 -2.1839953732,57.1616314191,609.6 -2.1771148595,57.1625096825,609.6 -2.1704124279,57.1637287773,609.6 -2.1639450998,57.1652783355,609.6 -2.1577679157,57.1671451771,609.6 -2.1519334705,57.1693134211,609.6 -2.1464914683,57.1717646198,609.6 -2.1414883007,57.174477914,609.6 -2.1369666526,57.1774302095,609.6 -2.1329651376,57.180596372,609.6 -2.129517968,57.18394943980001,609.6 -2.1266546597,57.18746085240001,609.6 -2.1243997775,57.1911006919,609.6 -2.1227727205,57.19483793769999,609.6 -2.1217875512,57.1986407293,609.6 -2.1214528694,57.2024766378,609.6 -2.1217717323,57.2063129417,609.6 -2.1227416214,57.2101169061,609.6 -2.1243544573,57.2138560622,609.6 -2.1265966617,57.2174984844,609.6 -2.1294492671,57.221013064,609.6 -2.1328880735,57.22436977550001,609.6 -2.1368838495,57.2275399342,609.6 -2.1414025785,57.2304964423,609.6 -2.1464057461,57.23321402219999,609.6 -2.1518506674,57.2356694335,609.6 -2.1576908515,57.2378416738,609.6 -2.1638763988,57.23971215899999,609.6 -2.1703544298,57.2412648843,609.6 -2.1770695392,57.24248656180001,609.6 -2.183964274,57.2433667355,609.6 -2.1909796289,57.2438978716,609.6 -2.1980555556,57.2440754236,609.6 + + + + +
+ + EGRU706B ABERDEEN/DYCE RWY 05 + 571012N 0021521W -
571035N 0021602W -
571046N 0021542W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571021N 0021503W -
571012N 0021521W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2558333333,57.1699,609.6 -2.2509389444,57.1724325,609.6 -2.2547998124,57.1745835737,609.6 -2.2583651059,57.1768803442,609.6 -2.2616161667,57.1793108611,609.6 -2.267225,57.1764083333,609.6 -2.2558333333,57.1699,609.6 + + + + +
+ + EGRU706C ABERDEEN/DYCE RWY 23 + 571428N 0020830W -
571405N 0020749W -
571347N 0020824W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571409N 0020908W -
571428N 0020830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1416416667,57.2412277778,609.6 -2.1521781389,57.2358029722,609.6 -2.1478649411,57.2339182045,609.6 -2.143814412,57.2318693419,609.6 -2.1400476944,57.2296671111,609.6 -2.1302277778,57.2347222222,609.6 -2.1416416667,57.2412277778,609.6 + + + + +
+ + EGRU706D ABERDEEN/DYCE RWY 14 + 571403N 0021541W -
571424N 0021456W -
571410N 0021434W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571349N 0021518W -
571403N 0021541W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.26135,57.2341222222,609.6 -2.2551375556,57.2302386389,609.6 -2.2513035743,57.2323996757,609.6 -2.2471918743,57.23440507859999,609.6 -2.2428238611,57.2362443889,609.6 -2.2488305556,57.24,609.6 -2.26135,57.2341222222,609.6 + + + + +
+ + EGRU706E ABERDEEN/DYCE RWY 32 + 571005N 0020803W -
570944N 0020848W -
571004N 0020920W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571025N 0020835W -
571005N 0020803W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.13425,57.1681777778,609.6 -2.1429397222,57.1736382222,609.6 -2.1469152275,57.1715566524,609.6 -2.1511562433,57.1696360549,609.6 -2.1556406944,57.1678863889,609.6 -2.1467444444,57.1622972222,609.6 -2.13425,57.1681777778,609.6 + + + + +
+ + EGRU706F ABERDEEN/DYCE RWY 16 + 571502N 0021434W -
571514N 0021338W -
571433N 0021308W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571421N 0021403W -
571502N 0021434W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2426722222,57.2505722222,609.6 -2.2342207778,57.2391555278,609.6 -2.2292543468,57.2404748588,609.6 -2.2241251251,57.2415964682,609.6 -2.2188598611,57.2425145,609.6 -2.2272916667,57.2539111111,609.6 -2.2426722222,57.2505722222,609.6 + + + + +
+ + EGRU706G ABERDEEN/DYCE RWY 34 + 570915N 0020914W -
570903N 0021009W -
570945N 0021039W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
570957N 0020944W -
570915N 0020914W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1537638889,57.1542722222,609.6 -2.1622190556,57.16575958329999,609.6 -2.1671869666,57.1644531612,609.6 -2.1723149548,57.1633444667,609.6 -2.1775764167,57.16243925000001,609.6 -2.1691027778,57.15093333330001,609.6 -2.1537638889,57.1542722222,609.6 + + + + +
+ + EGRU706I ABERDEEN/DYCE RWY 36 + 570935N 0021131W -
570935N 0021231W -
570941N 0021231W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
570940N 0021131W -
570935N 0021131W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1920326944,57.1597811944,609.6 -2.1920731667,57.1610514167,609.6 -2.1975928553,57.1609250685,609.6 -2.2031149457,57.1610151918,609.6 -2.20861075,57.1613213333,609.6 -2.2085559444,57.1596245,609.6 -2.1920326944,57.1597811944,609.6 + + + + +
+ + EGRU801A STORNOWAY + A circle, 2.5 NM radius, centred at 581256N 0061952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.331066666700001,58.2571659496,609.6 -6.3383433246,58.2569884183,609.6 -6.345557684200001,58.2564573442,609.6 -6.3526479856,58.2555772738,609.6 -6.3595535425,58.2543557411,609.6 -6.3662152656,58.2528032022,609.6 -6.3725761731,58.25093294489999,609.6 -6.3785818819,58.2487609742,609.6 -6.384181075199999,58.2463058737,609.6 -6.3893259432,58.2435886454,609.6 -6.3939725923,58.24063252890001,609.6 -6.3980814193,58.2374628007,609.6 -6.401617448199999,58.2341065568,609.6 -6.404550625800001,58.2305924798,609.6 -6.4068560739,58.2269505926,609.6 -6.4085142969,58.2232120008,609.6 -6.4095113418,58.21940862590001,609.6 -6.4098389112,58.2155729323,609.6 -6.409494426300001,58.21173765,609.6 -6.4084810417,58.2079354948,609.6 -6.4068076117,58.2041988897,609.6 -6.4044886068,58.2005596887,609.6 -6.4015439844,58.19704890570001,609.6 -6.3979990124,58.1936964513,609.6 -6.3938840486,58.1905308793,609.6 -6.3892342779,58.18757914419999,609.6 -6.3840894099,58.1848663732,609.6 -6.3784933381,58.182415654,609.6 -6.3724937661,58.1802478395,609.6 -6.3661418016,58.1783813719,609.6 -6.3594915233,58.1768321269,609.6 -6.352599523299999,58.17561328029999,609.6 -6.3455244289,58.17473519669999,609.6 -6.338326409000001,58.1742053424,609.6 -6.331066666700001,58.1740282223,609.6 -6.3238069243,58.1742053424,609.6 -6.316608904399999,58.17473519669999,609.6 -6.3095338101,58.17561328029999,609.6 -6.30264181,58.1768321269,609.6 -6.2959915317,58.1783813719,609.6 -6.2896395673,58.1802478395,609.6 -6.2836399953,58.182415654,609.6 -6.278043923499999,58.1848663732,609.6 -6.2728990554,58.18757914419999,609.6 -6.2682492848,58.1905308793,609.6 -6.264134320899999,58.1936964513,609.6 -6.2605893489,58.19704890570001,609.6 -6.2576447265,58.2005596887,609.6 -6.2553257217,58.2041988897,609.6 -6.2536522916,58.2079354948,609.6 -6.252638907099999,58.21173765,609.6 -6.252294422099999,58.2155729323,609.6 -6.2526219915,58.21940862590001,609.6 -6.2536190365,58.2232120008,609.6 -6.2552772594,58.2269505926,609.6 -6.257582707500001,58.2305924798,609.6 -6.260515885100001,58.2341065568,609.6 -6.264051914000001,58.2374628007,609.6 -6.268160741,58.24063252890001,609.6 -6.272807390099999,58.2435886454,609.6 -6.277952258200001,58.2463058737,609.6 -6.2835514515,58.2487609742,609.6 -6.2895571602,58.25093294489999,609.6 -6.2959180678,58.2528032022,609.6 -6.3025797908,58.2543557411,609.6 -6.3094853477,58.2555772738,609.6 -6.316575649199999,58.2564573442,609.6 -6.3237900087,58.2569884183,609.6 -6.331066666700001,58.2571659496,609.6 + + + + +
+ + EGRU801B STORNOWAY RWY 06 + 581108N 0062422W -
581136N 0062453W -
581150N 0062406W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581123N 0062333W -
581108N 0062422W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.40615,58.1854555556,609.6 -6.3925569167,58.1896305556,609.6 -6.3959452388,58.19203829709999,609.6 -6.3989963377,58.1945687406,609.6 -6.401694305600001,58.1972087222,609.6 -6.4146805556,58.1932194444,609.6 -6.40615,58.1854555556,609.6 + + + + +
+ + EGRU801C STORNOWAY RWY 24 + 581434N 0061510W -
581406N 0061439W -
581351N 0061528W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581420N 0061557W -
581434N 0061510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2528305556,58.24278055559999,609.6 -6.2657381389,58.2388406389,609.6 -6.2627313236,58.23629301300001,609.6 -6.2600812359,58.2336375699,609.6 -6.257801638899999,58.2308881667,609.6 -6.2442833333,58.23501388889999,609.6 -6.2528305556,58.24278055559999,609.6 + + + + +
+ + EGRU801D STORNOWAY RWY 18 + 581607N 0062059W -
581610N 0061958W -
581526N 0061949W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581523N 0062050W -
581607N 0062059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3497055556,58.2686027778,609.6 -6.3473553333,58.25626858330001,609.6 -6.3417523051,58.2567821575,609.6 -6.3360935191,58.2570813209,609.6 -6.3304085,58.2571645,609.6 -6.332752777799999,58.2694972222,609.6 -6.3497055556,58.2686027778,609.6 + + + + +
+ + EGRU801E STORNOWAY RWY 36 + 580941N 0061844W -
580938N 0061945W -
581027N 0061954W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581030N 0061853W -
580941N 0061844W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3122833333,58.1615194444,609.6 -6.3148175,58.1749232778,609.6 -6.3204085528,58.1744109341,609.6 -6.3260548434,58.174112552,609.6 -6.331727111099999,58.17402969439999,609.6 -6.3291861111,58.1606222222,609.6 -6.3122833333,58.1615194444,609.6 + + + + +
+ + EGRU802A WICK + A circle, 2 NM radius, centred at 582732N 0030535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0930555556,58.4921426198,609.6 -3.0995859271,58.4919662053,609.6 -3.1060468805,58.4914388369,609.6 -3.1123697415,58.49056612049999,609.6 -3.1184873162,58.4893573323,609.6 -3.1243346099,58.4878253192,609.6 -3.1298495226,58.4859863618,609.6 -3.134973512200001,58.4838599997,609.6 -3.1396522186,58.4814688224,609.6 -3.1438360416,58.4788382279,609.6 -3.1474806671,58.47599615130001,609.6 -3.1505475352,58.4729727663,609.6 -3.153004245900001,58.4698001639,609.6 -3.1548248976,58.4665120097,609.6 -3.1559903559,58.4631431864,609.6 -3.156488449699999,58.459729422,609.6 -3.156314091900001,58.4563069112,609.6 -3.1554693256,58.4529119305,609.6 -3.153963294,58.44958045469999,609.6 -3.1518121356,58.4463477753,609.6 -3.1490388059,58.44324812789999,609.6 -3.1456728272,58.44031433060001,609.6 -3.141749971,58.4375774374,609.6 -3.137311874499999,58.4350664112,609.6 -3.1324055973,58.4328078191,609.6 -3.1270831219,58.4308255521,609.6 -3.1214008035,58.429140575,609.6 -3.1154187757,58.4277707055,609.6 -3.1092003171,58.4267304272,609.6 -3.102811186099999,58.4260307381,609.6 -3.096318930799999,58.4256790346,609.6 -3.0897921803,58.4256790346,609.6 -3.083299925,58.4260307381,609.6 -3.0769107941,58.4267304272,609.6 -3.0706923354,58.4277707055,609.6 -3.0647103076,58.429140575,609.6 -3.0590279892,58.4308255521,609.6 -3.053705513800001,58.4328078191,609.6 -3.0487992366,58.4350664112,609.6 -3.0443611401,58.4375774374,609.6 -3.0404382839,58.44031433060001,609.6 -3.0370723052,58.44324812789999,609.6 -3.0342989755,58.4463477753,609.6 -3.0321478171,58.44958045469999,609.6 -3.0306417855,58.4529119305,609.6 -3.029797019200001,58.4563069112,609.6 -3.0296226614,58.459729422,609.6 -3.0301207552,58.4631431864,609.6 -3.0312862136,58.4665120097,609.6 -3.033106865200001,58.4698001639,609.6 -3.0355635759,58.4729727663,609.6 -3.038630444,58.47599615130001,609.6 -3.0422750695,58.4788382279,609.6 -3.0464588925,58.4814688224,609.6 -3.0511375989,58.4838599997,609.6 -3.0562615885,58.4859863618,609.6 -3.0617765012,58.4878253192,609.6 -3.0676237949,58.4893573323,609.6 -3.0737413696,58.49056612049999,609.6 -3.0800642307,58.4914388369,609.6 -3.086525184,58.4919662053,609.6 -3.0930555556,58.4921426198,609.6 + + + + +
+ + EGRU802B WICK RWY 13 + 582909N 0031033W -
582935N 0030956W -
582856N 0030818W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to
582830N 0030855W -
582909N 0031033W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.175763888900001,58.4857583333,609.6 -3.148531222199999,58.47504255560001,609.6 -3.1455271826,58.4775976674,609.6 -3.1420951993,58.48000044259999,609.6 -3.1382631667,58.4822312778,609.6 -3.16545,58.4929305556,609.6 -3.175763888900001,58.4857583333,609.6 + + + + +
+ + EGRU802C WICK RWY 31 + 582555N 0030040W -
582529N 0030117W -
582608N 0030253W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to
582633N 0030216W -
582555N 0030040W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0110833333,58.43201666669999,609.6 -3.0377739167,58.4425773056,609.6 -3.0408048412,58.4400322635,609.6 -3.0442604972,58.4376407495,609.6 -3.048112694399999,58.4354221944,609.6 -3.021375,58.4248444444,609.6 -3.0110833333,58.43201666669999,609.6 + + + + +
+ + EGRU803A KIRKWALL + A circle, 2 NM radius, centred at 585729N 0025402W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9004805556,58.9912650259,609.6 -2.9071051505,58.9910886218,609.6 -2.9136593217,58.99056128489999,609.6 -2.9200734005,58.9896886208,609.6 -2.9262792201,58.9884799056,609.6 -2.9322108453,58.9869479864,609.6 -2.9378052781,58.9851091435,609.6 -2.943003130800001,58.98298291610001,609.6 -2.9477492585,58.9805918934,609.6 -2.9519933464,58.97796147259999,609.6 -2.9556904427,58.9751195881,609.6 -2.958801434000001,58.9720964125,609.6 -2.9612934561,58.9689240353,609.6 -2.9631402382,58.9656361206,609.6 -2.9643223745,58.96226754890001,609.6 -2.9648275234,58.958854046,609.6 -2.9646505297,58.9554318039,609.6 -2.9637934711,58.9520370964,609.6 -2.962265627799999,58.9487058948,609.6 -2.9600833753,58.9454734876,609.6 -2.9572700039,58.9423741067,609.6 -2.9538554649,58.93944056660001,609.6 -2.9498760475,58.9367039177,609.6 -2.9453739904,58.9341931194,609.6 -2.940397031699999,58.9319347351,609.6 -2.9349979022,58.9299526531,609.6 -2.9292337674,58.9282678349,609.6 -2.9231656248,58.9268980957,609.6 -2.9168576612,58.9258579171,609.6 -2.9103765784,58.92515829529999,609.6 -2.9037908931,58.9248066258,609.6 -2.897170218,58.9248066258,609.6 -2.8905845327,58.92515829529999,609.6 -2.8841034499,58.9258579171,609.6 -2.8777954863,58.9268980957,609.6 -2.8717273437,58.9282678349,609.6 -2.8659632089,58.9299526531,609.6 -2.8605640794,58.9319347351,609.6 -2.8555871207,58.9341931194,609.6 -2.8510850636,58.9367039177,609.6 -2.8471056462,58.93944056660001,609.6 -2.8436911072,58.9423741067,609.6 -2.8408777358,58.9454734876,609.6 -2.8386954833,58.9487058948,609.6 -2.83716764,58.9520370964,609.6 -2.8363105814,58.9554318039,609.6 -2.8361335877,58.958854046,609.6 -2.8366387366,58.96226754890001,609.6 -2.8378208729,58.9656361206,609.6 -2.839667655,58.9689240353,609.6 -2.8421596771,58.9720964125,609.6 -2.8452706684,58.9751195881,609.6 -2.8489677647,58.97796147259999,609.6 -2.853211852599999,58.9805918934,609.6 -2.8579579804,58.98298291610001,609.6 -2.863155833,58.9851091435,609.6 -2.8687502658,58.9869479864,609.6 -2.874681890999999,58.9884799056,609.6 -2.8808877106,58.9896886208,609.6 -2.8873017895,58.99056128489999,609.6 -2.8938559607,58.9910886218,609.6 -2.9004805556,58.9912650259,609.6 + + + + +
+ + EGRU803B KIRKWALL RWY 09 + 585704N 0025947W -
585737N 0025950W -
585740N 0025753W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585707N 0025750W -
585704N 0025947W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9965222222,58.9512361111,609.6 -2.9637882778,58.9520225,609.6 -2.964578600499999,58.95499465839999,609.6 -2.9648472588,58.9579915212,609.6 -2.9645919444,58.9609886944,609.6 -2.997305555600001,58.9602027778,609.6 -2.9965222222,58.9512361111,609.6 + + + + +
+ + EGRU803C KIRKWALL RWY 27 + 585753N 0024808W -
585721N 0024806W -
585718N 0025011W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585750N 0025014W -
585753N 0024808W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8023416667,58.9647638889,609.6 -2.8371498056,58.9639711944,609.6 -2.8363708043,58.9609981919,609.6 -2.836113826,58.9580010211,609.6 -2.8363808333,58.9550040833,609.6 -2.8015527778,58.9557972222,609.6 -2.8023416667,58.9647638889,609.6 + + + + +
+ + EGRU803D KIRKWALL RWY 14 + 585932N 0025817W -
585953N 0025729W -
585907N 0025615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585845N 0025701W -
585932N 0025817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9713833333,58.9922083333,609.6 -2.9502969444,58.97907983330001,609.6 -2.9464099969,58.9813176402,609.6 -2.9421470098,58.9833649721,609.6 -2.937542805600001,58.98520505560001,609.6 -2.9579805556,58.9979333333,609.6 -2.9713833333,58.9922083333,609.6 + + + + +
+ + EGRU803E KIRKWALL RWY 32 + 585530N 0025028W -
585509N 0025116W -
585544N 0025211W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585603N 0025121W -
585530N 0025028W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8410083333,58.9249138889,609.6 -2.8557253611,58.93412377780001,609.6 -2.8600814518,58.9321339146,609.6 -2.8647667919,58.9303553359,609.6 -2.869743138900001,58.9288025278,609.6 -2.8543805556,58.9191916667,609.6 -2.8410083333,58.9249138889,609.6 + + + + +
+ + EGRU901A TRESCO + A circle, 2 NM radius, centred at 495644N 0061955W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.331898638900001,49.97877589519999,609.6 -6.3372082978,49.9785992755,609.6 -6.3424615574,49.9780712925,609.6 -6.3476026213,49.9771975541,609.6 -6.352576891799999,49.97598734069999,609.6 -6.357331553300001,49.9744535052,609.6 -6.3618161354,49.9726123364,609.6 -6.3659830515,49.9704833849,609.6 -6.3697881047,49.9680892542,609.6 -6.3731909576,49.9654553598,609.6 -6.3761555602,49.9626096581,609.6 -6.3786505308,49.9595823487,609.6 -6.3806494871,49.9564055526,609.6 -6.3821313228,49.9531129705,609.6 -6.383080428300001,49.94973952429999,609.6 -6.383486851199999,49.9463209866,609.6 -6.3833463981,49.94289360019999,609.6 -6.3826606734,49.9394936945,609.6 -6.3814370581,49.9361572996,609.6 -6.3796886263,49.9329197657,609.6 -6.3774340024,49.9298153883,609.6 -6.3746971601,49.9268770461,609.6 -6.371507164800001,49.92413585360001,609.6 -6.367897863500001,49.9216208323,609.6 -6.3639075243,49.9193586054,609.6 -6.3595784308,49.9173731162,609.6 -6.3549564343,49.9156853764,609.6 -6.3500904696,49.9143132447,609.6 -6.3450320383,49.91327123899999,609.6 -6.3398346667,49.91257038329999,609.6 -6.3345533424,49.9122180921,609.6 -6.3292439354,49.9122180921,609.6 -6.323962611,49.91257038329999,609.6 -6.3187652395,49.91327123899999,609.6 -6.3137068082,49.9143132447,609.6 -6.308840843499999,49.9156853764,609.6 -6.304218847,49.9173731162,609.6 -6.299889753499999,49.9193586054,609.6 -6.2958994143,49.9216208323,609.6 -6.2922901129,49.92413585360001,609.6 -6.2891001177,49.9268770461,609.6 -6.2863632754,49.9298153883,609.6 -6.2841086515,49.9329197657,609.6 -6.2823602197,49.9361572996,609.6 -6.2811366044,49.9394936945,609.6 -6.2804508797,49.94289360019999,609.6 -6.2803104265,49.9463209866,609.6 -6.280716849500001,49.94973952429999,609.6 -6.2816659549,49.9531129705,609.6 -6.283147790699999,49.9564055526,609.6 -6.285146747,49.9595823487,609.6 -6.2876417176,49.9626096581,609.6 -6.2906063202,49.9654553598,609.6 -6.294009173099999,49.9680892542,609.6 -6.297814226300001,49.9704833849,609.6 -6.3019811424,49.9726123364,609.6 -6.3064657245,49.9744535052,609.6 -6.311220386,49.97598734069999,609.6 -6.3161946565,49.9771975541,609.6 -6.3213357204,49.9780712925,609.6 -6.32658898,49.9785992755,609.6 -6.331898638900001,49.97877589519999,609.6 + + + + +
+ + EGRU902A SCILLY ISLES/ST MARY'S + A circle, 2 NM radius, centred at 495448N 0061730W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.291758333300001,49.9465871643,609.6 -6.297064453000001,49.94641054380001,609.6 -6.3023142112,49.94588255819999,609.6 -6.3074518487,49.9450088157,609.6 -6.312422804300001,49.9437985963,609.6 -6.3171742977,49.9422647534,609.6 -6.321655892400001,49.9404235756,609.6 -6.3258200333,49.9382946135,609.6 -6.3296225531,49.9359004707,609.6 -6.333023141199999,49.933266563,609.6 -6.3359857716,49.9304208467,609.6 -6.338479083399999,49.9273935215,609.6 -6.3404767119,49.9242167086,609.6 -6.3419575646,49.9209241088,609.6 -6.342906042,49.91755064430001,609.6 -6.3433121985,49.9141320877,609.6 -6.343171842999999,49.9107046821,609.6 -6.3424865789,49.9073047571,609.6 -6.341263782,49.903968343,609.6 -6.3395165174,49.9007307902,609.6 -6.3372633973,49.8976263944,609.6 -6.334528379100001,49.8946880347,609.6 -6.3313405088,49.8919468255,609.6 -6.3277336107,49.8894317889,609.6 -6.3237459277,49.887169548,609.6 -6.319419715,49.8851840465,609.6 -6.3148007936,49.8834962961,609.6 -6.3099380657,49.8821241558,609.6 -6.3048829988,49.8810821435,609.6 -6.2996890837,49.8803812834,609.6 -6.2944112715,49.8800289899,609.6 -6.2891053952,49.8800289899,609.6 -6.283827583,49.8803812834,609.6 -6.2786336679,49.8810821435,609.6 -6.273578601,49.8821241558,609.6 -6.268715873,49.8834962961,609.6 -6.2640969517,49.8851840465,609.6 -6.259770739,49.887169548,609.6 -6.2557830559,49.8894317889,609.6 -6.2521761579,49.8919468255,609.6 -6.2489882876,49.8946880347,609.6 -6.2462532693,49.8976263944,609.6 -6.2440001492,49.9007307902,609.6 -6.242252884699999,49.903968343,609.6 -6.241030087699999,49.9073047571,609.6 -6.240344823599999,49.9107046821,609.6 -6.2402044682,49.9141320877,609.6 -6.240610624600001,49.91755064430001,609.6 -6.2415591021,49.9209241088,609.6 -6.2430399548,49.9242167086,609.6 -6.245037583199999,49.9273935215,609.6 -6.2475308951,49.9304208467,609.6 -6.2504935255,49.933266563,609.6 -6.253894113600001,49.9359004707,609.6 -6.257696633300001,49.9382946135,609.6 -6.261860774300001,49.9404235756,609.6 -6.2663423689,49.9422647534,609.6 -6.271093862300001,49.9437985963,609.6 -6.276064818000001,49.9450088157,609.6 -6.281202455399999,49.94588255819999,609.6 -6.286452213600001,49.94641054380001,609.6 -6.291758333300001,49.9465871643,609.6 + + + + +
+ + EGRU902B SCILLY ISLES/ST MARY'S RWY 09 + 495423N 0062152W -
495456N 0062155W -
495458N 0062035W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495426N 0062033W -
495423N 0062152W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3645694444,49.9064916667,609.6 -6.34246425,49.9072264167,609.6 -6.343105279199999,49.9102031456,609.6 -6.343328192399999,49.91320507210001,609.6 -6.343131083300001,49.91620775,609.6 -6.3652722222,49.91547222219999,609.6 -6.3645694444,49.9064916667,609.6 + + + + +
+ + EGRU902C SCILLY ISLES/ST MARY'S RWY 27 + 495513N 0061309W -
495441N 0061307W -
495438N 0061425W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495510N 0061428W -
495513N 0061309W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2192583333,49.9202444444,609.6 -6.2411032222,49.9195422222,609.6 -6.2404376283,49.91656837119999,609.6 -6.2401899616,49.9135678841,609.6 -6.2403621389,49.91056519440001,609.6 -6.2185527778,49.9112666667,609.6 -6.2192583333,49.9202444444,609.6 + + + + +
+ + EGRU902D SCILLY ISLES/ST MARY'S RWY 14 + 495647N 0062042W -
495709N 0062004W -
495629N 0061911W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495607N 0061949W -
495647N 0062042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.345122222200001,49.946525,609.6 -6.330323583299999,49.9354010833,609.6 -6.3270783713,49.93755607170001,609.6 -6.3235450932,49.9395133576,609.6 -6.3197525278,49.9412569722,609.6 -6.3345444444,49.9523777778,609.6 -6.345122222200001,49.946525,609.6 + + + + +
+ + EGRU902E SCILLY ISLES/ST MARY'S RWY 32 + 495248N 0061419W -
495227N 0061457W -
495307N 0061550W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495328N 0061512W -
495248N 0061419W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2384777778,49.8800277778,609.6 -6.2532298056,49.8911571944,609.6 -6.2564752205,49.8890044172,609.6 -6.260007513899999,49.88704931070001,609.6 -6.2637979444,49.8853077778,609.6 -6.2490388889,49.87417499999999,609.6 -6.2384777778,49.8800277778,609.6 + + + + +
+ + EGRU903A EDAY + A circle, 2 NM radius, centred at 591125N 0024621W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7724055556,59.2236221598,609.6 -2.7790751247,59.22344576049999,609.6 -2.7856737902,59.2229184379,609.6 -2.7921314086,59.2220457978,609.6 -2.7983793486,59.2208371162,609.6 -2.8043512262,59.2193052401,609.6 -2.8099836148,59.2174664497,609.6 -2.8152167228,59.21534028420001,609.6 -2.8199950311,59.2129493325,609.6 -2.824267883600001,59.2103189917,609.6 -2.8279900241,59.2074771956,609.6 -2.831122075,59.2044541165,609.6 -2.8336309507,59.20128184319999,609.6 -2.835490204,59.19799403889999,609.6 -2.8366802999,59.1946255834,609.6 -2.8371888152,59.19121220139999,609.6 -2.8370105624,59.1877900836,609.6 -2.8361476357,59.18439550250001,609.6 -2.8346093806,59.181064428,609.6 -2.832412286,59.1778321468,609.6 -2.8295798019,59.1747328895,609.6 -2.8261420844,59.1717994687,609.6 -2.8221356698,59.1690629331,609.6 -2.8176030839,59.1665522406,609.6 -2.812592388700001,59.16429395290001,609.6 -2.8071566721,59.1623119567,609.6 -2.8013534865,59.16062721239999,609.6 -2.7952442416,59.1592575338,609.6 -2.7888935577,59.15821740150001,609.6 -2.7823685869,59.1575178111,609.6 -2.7757383079,59.1571661574,609.6 -2.7690728032,59.1571661574,609.6 -2.7624425242,59.1575178111,609.6 -2.7559175534,59.15821740150001,609.6 -2.7495668695,59.1592575338,609.6 -2.7434576246,59.16062721239999,609.6 -2.737654439,59.1623119567,609.6 -2.7322187224,59.16429395290001,609.6 -2.7272080272,59.1665522406,609.6 -2.7226754413,59.1690629331,609.6 -2.7186690267,59.1717994687,609.6 -2.7152313092,59.1747328895,609.6 -2.7123988252,59.1778321468,609.6 -2.7102017305,59.181064428,609.6 -2.7086634754,59.18439550250001,609.6 -2.7078005487,59.1877900836,609.6 -2.7076222959,59.19121220139999,609.6 -2.7081308112,59.1946255834,609.6 -2.7093209071,59.19799403889999,609.6 -2.7111801604,59.20128184319999,609.6 -2.7136890362,59.2044541165,609.6 -2.716821087,59.2074771956,609.6 -2.7205432276,59.2103189917,609.6 -2.72481608,59.2129493325,609.6 -2.7295943883,59.21534028420001,609.6 -2.7348274963,59.2174664497,609.6 -2.7404598849,59.2193052401,609.6 -2.7464317625,59.2208371162,609.6 -2.7526797025,59.2220457978,609.6 -2.7591373209,59.2229184379,609.6 -2.7657359864,59.22344576049999,609.6 -2.7724055556,59.2236221598,609.6 + + + + +
+ + EGRU904A STRONSAY + A circle, 2 NM radius, centred at 590919N 0023830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6415277778,59.1885278961,609.6 -2.648190508,59.1883514961,609.6 -2.6547824075,59.1878241714,609.6 -2.6612334051,59.1869515277,609.6 -2.6674749401,59.18574284110001,609.6 -2.6734406968,59.1842109585,609.6 -2.6790673137,59.1823721602,609.6 -2.6842950607,59.1802459854,609.6 -2.6890684755,59.177855023,609.6 -2.6933369539,59.1752246701,609.6 -2.6970552861,59.1723828607,609.6 -2.7001841346,59.1693597671,609.6 -2.7026904476,59.1661874781,609.6 -2.7045478046,59.1628996572,609.6 -2.7057366901,59.1595311842,609.6 -2.7062446936,59.156117784,609.6 -2.7060666323,59.1526956474,609.6 -2.7052045979,59.1493010472,609.6 -2.7036679261,59.1459699536,609.6 -2.7014730884,59.14273765339999,609.6 -2.6986435108,59.13963837739999,609.6 -2.6952093178,59.1367049386,609.6 -2.6912070085,59.1339683859,609.6 -2.686679065,59.1314576774,609.6 -2.6816734998,59.1291993752,609.6 -2.6762433467,59.12721736610001,609.6 -2.6704460993,59.1255326105,609.6 -2.6643431045,59.1241629228,609.6 -2.6579989168,59.1231227835,609.6 -2.6514806197,59.12242318840001,609.6 -2.6448571217,59.12207153229999,609.6 -2.6381984339,59.12207153229999,609.6 -2.6315749359,59.12242318840001,609.6 -2.6250566388,59.1231227835,609.6 -2.618712451,59.1241629228,609.6 -2.6126094562,59.1255326105,609.6 -2.6068122088,59.12721736610001,609.6 -2.6013820557,59.1291993752,609.6 -2.5963764906,59.1314576774,609.6 -2.591848547,59.1339683859,609.6 -2.5878462377,59.1367049386,609.6 -2.5844120448,59.13963837739999,609.6 -2.5815824671,59.14273765339999,609.6 -2.5793876295,59.1459699536,609.6 -2.5778509576,59.1493010472,609.6 -2.5769889233,59.1526956474,609.6 -2.576810862,59.156117784,609.6 -2.5773188654,59.1595311842,609.6 -2.578507751,59.1628996572,609.6 -2.5803651079,59.1661874781,609.6 -2.5828714209,59.1693597671,609.6 -2.5860002694,59.1723828607,609.6 -2.5897186017,59.1752246701,609.6 -2.5939870801,59.177855023,609.6 -2.5987604949,59.1802459854,609.6 -2.6039882418,59.1823721602,609.6 -2.6096148588,59.1842109585,609.6 -2.6155806155,59.18574284110001,609.6 -2.6218221505,59.1869515277,609.6 -2.6282731481,59.1878241714,609.6 -2.6348650476,59.1883514961,609.6 -2.6415277778,59.1885278961,609.6 + + + + +
+ + EGRU905A SANDAY + A circle, 2 NM radius, centred at 591501N 0023430W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.575,59.28341907410001,609.6 -2.5816812603,59.2832426761,609.6 -2.5882914921,59.2827153572,609.6 -2.5947604287,59.2818427233,609.6 -2.601019318,59.2806340502,609.6 -2.6070016592,59.2791021852,609.6 -2.6126439145,59.2772634082,609.6 -2.6178861871,59.2751372585,609.6 -2.6226728607,59.27274632500001,609.6 -2.6269531904,59.27011600469999,609.6 -2.6306818411,59.2672742313,609.6 -2.6338193664,59.2642511769,609.6 -2.6363326231,59.2610789301,609.6 -2.6381951183,59.2577911543,609.6 -2.6393872831,59.2544227286,609.6 -2.6398966734,59.2510093776,609.6 -2.6397180932,59.2475872917,609.6 -2.638853641,59.244192743,609.6 -2.6373126792,59.2408617011,609.6 -2.6351117263,59.2376294523,609.6 -2.6322742739,59.2345302267,609.6 -2.628830531,59.2315968366,609.6 -2.6248170985,59.2288603301,609.6 -2.6202765767,59.2263496648,609.6 -2.6152571117,59.224091402,609.6 -2.6098118844,59.22210942789999,609.6 -2.6039985477,59.2204247025,609.6 -2.5978786183,59.2190550394,609.6 -2.5915168294,59.21801491909999,609.6 -2.58498045,59.21731533679999,609.6 -2.578338579,59.2169636871,609.6 -2.571661421,59.2169636871,609.6 -2.56501955,59.21731533679999,609.6 -2.5584831706,59.21801491909999,609.6 -2.5521213817,59.2190550394,609.6 -2.5460014523,59.2204247025,609.6 -2.5401881156,59.22210942789999,609.6 -2.5347428883,59.224091402,609.6 -2.5297234233,59.2263496648,609.6 -2.5251829015,59.2288603301,609.6 -2.521169469,59.2315968366,609.6 -2.5177257261,59.2345302267,609.6 -2.5148882737,59.2376294523,609.6 -2.5126873208,59.2408617011,609.6 -2.511146359,59.244192743,609.6 -2.5102819068,59.2475872917,609.6 -2.5101033266,59.2510093776,609.6 -2.5106127169,59.2544227286,609.6 -2.5118048817,59.2577911543,609.6 -2.5136673769,59.2610789301,609.6 -2.5161806336,59.2642511769,609.6 -2.5193181589,59.2672742313,609.6 -2.5230468096,59.27011600469999,609.6 -2.5273271393,59.27274632500001,609.6 -2.5321138129,59.2751372585,609.6 -2.5373560855,59.2772634082,609.6 -2.5429983408,59.2791021852,609.6 -2.548980682,59.2806340502,609.6 -2.5552395713,59.2818427233,609.6 -2.5617085079,59.2827153572,609.6 -2.5683187397,59.2832426761,609.6 -2.575,59.28341907410001,609.6 + + + + +
+ + EGRU906A NORTH RONALDSAY + A circle, 2 NM radius, centred at 592203N 0022605W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4346972222,59.4008184708,609.6 -2.4414015769,59.4006420752,609.6 -2.4480346567,59.4001147635,609.6 -2.454525951,59.3992421415,609.6 -2.4608064692,59.39803348529999,609.6 -2.4668094801,59.3965016417,609.6 -2.4724712256,59.3946628911,609.6 -2.4777316019,59.3925367724,609.6 -2.4825348001,59.3901458745,609.6 -2.4868299002,59.38751559430001,609.6 -2.4905714109,59.3846738652,609.6 -2.4937197499,59.3816508592,609.6 -2.4962416607,59.3784786646,609.6 -2.4981105595,59.3751909442,609.6 -2.4993068112,59.37182257689999,609.6 -2.4998179299,59.36840928670001,609.6 -2.4996387027,59.3649872634,609.6 -2.4987712369,59.3615927783,609.6 -2.4972249285,59.35826180039999,609.6 -2.4950163539,59.3550296151,609.6 -2.492169087,59.3519304518,609.6 -2.4887134419,59.3489971217,609.6 -2.4846861463,59.3462606725,609.6 -2.4801299481,59.3437500605,609.6 -2.4750931596,59.3414918463,609.6 -2.4696291451,59.3395099156,609.6 -2.4637957561,59.33782522749999,609.6 -2.457654721,59.336455595,609.6 -2.4512709957,59.33541549810001,609.6 -2.4447120802,59.33471593150001,609.6 -2.438047311,59.33436428990001,609.6 -2.4313471335,59.33436428990001,609.6 -2.4246823642,59.33471593150001,609.6 -2.4181234487,59.33541549810001,609.6 -2.4117397234,59.336455595,609.6 -2.4055986884,59.33782522749999,609.6 -2.3997652994,59.3395099156,609.6 -2.3943012849,59.3414918463,609.6 -2.3892644964,59.3437500605,609.6 -2.3847082982,59.3462606725,609.6 -2.3806810026,59.3489971217,609.6 -2.3772253575,59.3519304518,609.6 -2.3743780906,59.3550296151,609.6 -2.372169516,59.35826180039999,609.6 -2.3706232075,59.3615927783,609.6 -2.3697557417,59.3649872634,609.6 -2.3695765146,59.36840928670001,609.6 -2.3700876332,59.37182257689999,609.6 -2.3712838849,59.3751909442,609.6 -2.3731527837,59.3784786646,609.6 -2.3756746945,59.3816508592,609.6 -2.3788230336,59.3846738652,609.6 -2.3825645443,59.38751559430001,609.6 -2.3868596444,59.3901458745,609.6 -2.3916628426,59.3925367724,609.6 -2.3969232188,59.3946628911,609.6 -2.4025849643,59.3965016417,609.6 -2.4085879752,59.39803348529999,609.6 -2.4148684935,59.3992421415,609.6 -2.4213597877,59.4001147635,609.6 -2.4279928675,59.4006420752,609.6 -2.4346972222,59.4008184708,609.6 + + + + +
+ + EGRU907A FAIR ISLE + A circle, 2 NM radius, centred at 593205N 0013743W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6285111111,59.5679759474,609.6 -1.6352486751,59.5677995552,609.6 -1.6419146096,59.56727225369999,609.6 -1.6484380536,59.56639964869999,609.6 -1.6547496737,59.56519101619999,609.6 -1.660782407,59.5636592032,609.6 -1.6664721789,59.5618204898,609.6 -1.6717585875,59.55969441500001,609.6 -1.6765855474,59.5573035675,609.6 -1.6809018868,59.554673344,609.6 -1.6846618895,59.5518316778,609.6 -1.6878257782,59.5488087405,609.6 -1.6903601329,59.5456366198,609.6 -1.6922382397,59.5423489782,609.6 -1.6934403679,59.53898069379999,609.6 -1.6939539715,59.5355674899,609.6 -1.6937738138,59.5321455553,609.6 -1.6929020143,59.5287511606,609.6 -1.6913480172,59.5254202735,609.6 -1.6891284828,59.5221881786,609.6 -1.6862671028,59.5190891037,609.6 -1.6827943426,59.5161558591,609.6 -1.6787471124,59.5134194912,609.6 -1.674168372,59.510908955,609.6 -1.669106673,59.5086508102,609.6 -1.6636156433,59.5066689411,609.6 -1.6577534201,59.504984306,609.6 -1.6515820362,59.503614717,609.6 -1.6451667673,59.5025746534,609.6 -1.6385754462,59.5018751093,609.6 -1.6318777503,59.501523479,609.6 -1.6251444719,59.501523479,609.6 -1.6184467761,59.5018751093,609.6 -1.6118554549,59.5025746534,609.6 -1.605440186,59.503614717,609.6 -1.5992688021,59.504984306,609.6 -1.5934065789,59.5066689411,609.6 -1.5879155492,59.5086508102,609.6 -1.5828538502,59.510908955,609.6 -1.5782751099,59.5134194912,609.6 -1.5742278797,59.5161558591,609.6 -1.5707551194,59.5190891037,609.6 -1.5678937394,59.5221881786,609.6 -1.565674205,59.5254202735,609.6 -1.5641202079,59.5287511606,609.6 -1.5632484084,59.5321455553,609.6 -1.5630682507,59.5355674899,609.6 -1.5635818543,59.53898069379999,609.6 -1.5647839825,59.5423489782,609.6 -1.5666620893,59.5456366198,609.6 -1.569196444,59.5488087405,609.6 -1.5723603328,59.5518316778,609.6 -1.5761203355,59.554673344,609.6 -1.5804366748,59.5573035675,609.6 -1.5852636348,59.55969441500001,609.6 -1.5905500433,59.5618204898,609.6 -1.5962398152,59.5636592032,609.6 -1.6022725485,59.56519101619999,609.6 -1.6085841686,59.56639964869999,609.6 -1.6151076126,59.56727225369999,609.6 -1.6217735472,59.5677995552,609.6 -1.6285111111,59.5679759474,609.6 + + + + +
+ + EGRU908A SUMBURGH + A circle, 2 NM radius, centred at 595253N 0011738W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2938289167,59.91472354030001,609.6 -1.3006366179,59.914547155,609.6 -1.3073719411,59.9140198744,609.6 -1.3139632846,59.9131473042,609.6 -1.3203405909,59.9119387204,609.6 -1.3264360969,59.91040697,609.6 -1.3321850596,59.908568333,609.6 -1.3375264472,59.9064423484,609.6 -1.3424035907,59.9040516045,609.6 -1.346764786,59.9014214977,609.6 -1.3505638424,59.8985799609,609.6 -1.3537605706,59.8955571648,609.6 -1.3563212053,59.89238519650001,609.6 -1.3582187579,59.8890977171,609.6 -1.3594332958,59.8857296036,609.6 -1.3599521463,59.88231657770001,609.6 -1.3597700222,59.87889482640001,609.6 -1.3588890691,59.8755006183,609.6 -1.3573188329,59.8721699191,609.6 -1.3550761509,59.86893801069999,609.6 -1.3521849641,59.8658391189,609.6 -1.3486760571,59.8629060512,609.6 -1.3445867258,59.8601698514,609.6 -1.3399603776,59.8576594723,609.6 -1.3348460691,59.855401471,609.6 -1.3292979853,59.8534197296,609.6 -1.3233748663,59.8517352043,609.6 -1.317139388,59.85036570540001,609.6 -1.310657502,59.8493257108,609.6 -1.3039977428,59.84862621330001,609.6 -1.2972305088,59.8482746066,609.6 -1.2904273245,59.8482746066,609.6 -1.2836600906,59.84862621330001,609.6 -1.2770003314,59.8493257108,609.6 -1.2705184453,59.85036570540001,609.6 -1.264282967,59.8517352043,609.6 -1.258359848,59.8534197296,609.6 -1.2528117642,59.855401471,609.6 -1.2476974557,59.8576594723,609.6 -1.2430711075,59.8601698514,609.6 -1.2389817762,59.8629060512,609.6 -1.2354728692,59.8658391189,609.6 -1.2325816824,59.86893801069999,609.6 -1.2303390004,59.8721699191,609.6 -1.2287687643,59.8755006183,609.6 -1.2278878111,59.87889482640001,609.6 -1.227705687,59.88231657770001,609.6 -1.2282245375,59.8857296036,609.6 -1.2294390754,59.8890977171,609.6 -1.231336628,59.89238519650001,609.6 -1.2338972627,59.8955571648,609.6 -1.237093991,59.8985799609,609.6 -1.2408930474,59.9014214977,609.6 -1.2452542426,59.9040516045,609.6 -1.2501313861,59.9064423484,609.6 -1.2554727738,59.908568333,609.6 -1.2612217364,59.91040697,609.6 -1.2673172424,59.9119387204,609.6 -1.2736945487,59.9131473042,609.6 -1.2802858923,59.9140198744,609.6 -1.2870212155,59.914547155,609.6 -1.2938289167,59.91472354030001,609.6 + + + + +
+ + EGRU908B SUMBURGH RWY 06 + 595040N 0012125W -
595106N 0012203W -
595137N 0012040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595114N 0011952W -
595040N 0012125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3568085833,59.8444108056,609.6 -1.3311036389,59.85401805560001,609.6 -1.3359630795,59.8558562601,609.6 -1.3404666687,59.8579111898,609.6 -1.3445763333,59.8601654722,609.6 -1.3674341667,59.8516208056,609.6 -1.3568085833,59.8444108056,609.6 + + + + +
+ + EGRU908C SUMBURGH RWY 24 + 595429N 0011258W -
595403N 0011220W -
595329N 0011351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595359N 0011419W -
595429N 0011258W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2162301667,59.90798866669999,609.6 -1.2384997778,59.89970961110001,609.6 -1.2354006971,59.897077012,609.6 -1.2327967446,59.8943124159,609.6 -1.2307098611,59.89143925,609.6 -1.2055865833,59.9007787222,609.6 -1.2162301667,59.90798866669999,609.6 + + + + +
+ + EGRU908D SUMBURGH RWY 09 + 595217N 0012335W -
595249N 0012342W -
595256N 0012136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595224N 0012129W -
595217N 0012335W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3929947222,59.87130875,609.6 -1.3579365,59.87331869439999,609.6 -1.3591408487,59.8762570415,609.6 -1.359813575,59.8792380001,609.6 -1.3599490556,59.8822373056,609.6 -1.3949956111,59.88022805560001,609.6 -1.3929947222,59.87130875,609.6 + + + + +
+ + EGRU908E SUMBURGH RWY 27 + 595330N 0011140W -
595258N 0011133W -
595251N 0011340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595323N 0011347W -
595330N 0011140W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.19437,59.8916009167,609.6 -1.2296873611,59.8896215833,609.6 -1.2284900505,59.8866824629,609.6 -1.2278249785,59.88370106230001,609.6 -1.2276974167,59.88070166670001,609.6 -1.1923684444,59.88268163890001,609.6 -1.19437,59.8916009167,609.6 + + + + +
+ + EGRU908F SUMBURGH RWY 15 + 595450N 0012132W -
595509N 0012041W -
595434N 0011948W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595412N 0012037W -
595450N 0012132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3589489444,59.9138691667,609.6 -1.3434973056,59.9034362778,609.6 -1.3393430101,59.9056034287,609.6 -1.3348151617,59.9075729269,609.6 -1.3299508611,59.9093286111,609.6 -1.34459625,59.9192197778,609.6 -1.3589489444,59.9138691667,609.6 + + + + +
+ + EGRU908G SUMBURGH RWY 33 + 595022N 0011337W -
595003N 0011429W -
595104N 0011559W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595122N 0011504W -
595022N 0011337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.226986,59.8395753611,609.6 -1.2512414722,59.8560408056,609.6 -1.2559873152,59.8542101142,609.6 -1.2610422146,59.8526025447,609.6 -1.2663648333,59.8512312222,609.6 -1.2413044167,59.8342246667,609.6 -1.226986,59.8395753611,609.6 + + + + +
+ + EGRU909A WESTRAY + A circle, 2 NM radius, centred at 592100N 0025700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.949875,59.3832852275,609.6 -2.9565758937,59.3831088315,609.6 -2.9632055494,59.3825815187,609.6 -2.969693493,59.381708895,609.6 -2.9759707698,59.38050023620001,609.6 -2.9819706831,59.3789683895,609.6 -2.9876295077,59.37712963489999,609.6 -2.9928871709,59.3750035117,609.6 -2.997687892600001,59.3726126084,609.6 -3.0019807792,59.3699823222,609.6 -3.0057203627,59.3671405865,609.6 -3.0088670811,59.3641175733,609.6 -3.011387694999999,59.36094537089999,609.6 -3.0132556341,59.3576576423,609.6 -3.0144512734,59.35428926630001,609.6 -3.014962133,59.350875967,609.6 -3.014783002799999,59.34745393429999,609.6 -3.0139159887,59.3440594397,609.6 -3.0123704815,59.3407284522,609.6 -3.0101630491,59.3374962575,609.6 -3.0073172531,59.3343970849,609.6 -3.0038633917,59.3314637459,609.6 -2.9998381737,59.3287272881,609.6 -2.9952843248,59.3262166681,609.6 -2.9902501325,59.32395844669999,609.6 -2.9847889335,59.3219765095,609.6 -2.9789585496,59.32029181579999,609.6 -2.9728206775,59.31892217879999,609.6 -2.9664402396,59.3178820784,609.6 -2.9598847015,59.3171825094,609.6 -2.9532233639,59.3168308666,609.6 -2.946526636100001,59.3168308666,609.6 -2.9398652985,59.3171825094,609.6 -2.9333097604,59.3178820784,609.6 -2.9269293225,59.31892217879999,609.6 -2.920791450399999,59.32029181579999,609.6 -2.9149610665,59.3219765095,609.6 -2.9094998675,59.32395844669999,609.6 -2.9044656752,59.3262166681,609.6 -2.8999118263,59.3287272881,609.6 -2.895886608300001,59.3314637459,609.6 -2.8924327469,59.3343970849,609.6 -2.8895869509,59.3374962575,609.6 -2.8873795185,59.3407284522,609.6 -2.8858340113,59.3440594397,609.6 -2.8849669972,59.34745393429999,609.6 -2.884787867,59.350875967,609.6 -2.8852987266,59.35428926630001,609.6 -2.8864943659,59.3576576423,609.6 -2.888362305,59.36094537089999,609.6 -2.8908829189,59.3641175733,609.6 -2.8940296373,59.3671405865,609.6 -2.8977692208,59.3699823222,609.6 -2.9020621074,59.3726126084,609.6 -2.9068628291,59.3750035117,609.6 -2.9121204923,59.37712963489999,609.6 -2.9177793169,59.3789683895,609.6 -2.9237792302,59.38050023620001,609.6 -2.930056507,59.381708895,609.6 -2.9365444506,59.3825815187,609.6 -2.943174106299999,59.3831088315,609.6 -2.949875,59.3832852275,609.6 + + + + +
+ + EGRU910A PAPA WESTRAY + A circle, 2 NM radius, centred at 592103N 0025401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.90035,59.3841574452,609.6 -2.9070510658,59.3839810493,609.6 -2.9136808917,59.3834537366,609.6 -2.9201690019,59.38258111289999,609.6 -2.9264464399,59.3813724543,609.6 -2.9324465072,59.37984060769999,609.6 -2.938105477,59.3780018533,609.6 -2.943363275,59.3758757303,609.6 -2.9481641199,59.37348482729999,609.6 -2.9524571166,59.3708545414,609.6 -2.9561967958,59.368012806,609.6 -2.9593435949,59.3649897932,609.6 -2.9618642732,59.3618175912,609.6 -2.9637322601,59.35852986290001,609.6 -2.9649279298,59.3551614874,609.6 -2.9654388023,59.3517481885,609.6 -2.965259667299999,59.3483261563,609.6 -2.9643926307,59.3449316622,609.6 -2.9628470836,59.3416006752,609.6 -2.9606395945,59.338368481,609.6 -2.9577937253,59.33526930879999,609.6 -2.9543397752,59.3323359702,609.6 -2.9503144539,59.3295995128,609.6 -2.945760488199999,59.32708889330001,609.6 -2.940726166800001,59.3248306723,609.6 -2.9352648279,59.3228487353,609.6 -2.9294342945,59.3211640419,609.6 -2.9232962652,59.31979440509999,609.6 -2.9169156639,59.3187543049,609.6 -2.9103599579,59.3180547361,609.6 -2.903698449599999,59.3177030933,609.6 -2.8970015504,59.3177030933,609.6 -2.8903400421,59.3180547361,609.6 -2.883784336100001,59.3187543049,609.6 -2.877403734800001,59.31979440509999,609.6 -2.8712657055,59.3211640419,609.6 -2.8654351721,59.3228487353,609.6 -2.8599738332,59.3248306723,609.6 -2.8549395118,59.32708889330001,609.6 -2.850385546100001,59.3295995128,609.6 -2.8463602248,59.3323359702,609.6 -2.842906274699999,59.33526930879999,609.6 -2.8400604055,59.338368481,609.6 -2.8378529164,59.3416006752,609.6 -2.8363073693,59.3449316622,609.6 -2.8354403327,59.3483261563,609.6 -2.8352611977,59.3517481885,609.6 -2.8357720702,59.3551614874,609.6 -2.8369677399,59.35852986290001,609.6 -2.8388357268,59.3618175912,609.6 -2.8413564051,59.3649897932,609.6 -2.8445032042,59.368012806,609.6 -2.8482428834,59.3708545414,609.6 -2.8525358801,59.37348482729999,609.6 -2.857336725000001,59.3758757303,609.6 -2.862594523,59.3780018533,609.6 -2.868253492800001,59.37984060769999,609.6 -2.8742535601,59.3813724543,609.6 -2.880530998099999,59.38258111289999,609.6 -2.8870191083,59.3834537366,609.6 -2.8936489342,59.3839810493,609.6 -2.90035,59.3841574452,609.6 + + + + +
+ + Basildon University Hospital + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4518516456687849,51.55800083830794,58.08521858368528 + + + + Basildon University Hospital Accident and ... + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4515649145776108,51.55862862589095,63.25143581313333 + + + + Mulberry Assessment Centre, Basildon Hospital + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4543600102226297,51.55892826898683,61.12414806775797 + + + + Basildon Mental Health Unity + + 0.4521352191627104 + 51.5591080503393 + 53.94959600323294 + 53.28182780882707 + 59.94900317415277 + 35 + 990.0404276922927 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4504371056189932,51.55704006258427,58.6390360083163 + + + + Basildon Hospital Simulation Suite + + 0.4521352191627104 + 51.5591080503393 + 53.94959600323294 + 53.28182780882707 + 59.94900317415277 + 35 + 990.0404276922927 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4483682821085228,51.55806422210383,63.90305654267409 + + + + Fryerns Medical Centre + + 0.4752487883464585 + 51.57345754883367 + 36.16638769277598 + 53.29440376545357 + 59.96137223993925 + 35 + 2579.139101160108 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4898574326064499,51.57853506709266,17.93325067593601 + + + + Murree Medical Centre + + 0.4752487883464585 + 51.57345754883367 + 36.16638769277598 + 53.29440376545357 + 59.96137223993925 + 35 + 2579.139101160108 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4813540951236296,51.57658601871081,32.47146360214328 + + + + St Peter's Hospital + + 0.6771628259292584 + 51.72855213684512 + 22.87229294006159 + 53.59273614142136 + 59.96772415652145 + 35 + 3395.186773824971 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6715336638568048,51.73008053466475,37.51985194938187 + + + + Halstead Hospital + + 0.6245231935558504 + 51.93606495933507 + 76.48619882270123 + 53.37055133585243 + 59.97207446579549 + 35 + 3954.119959588861 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6379421359890148,51.94822718909322,56.15721830449306 + + + + Braintree Community Hospital + + 0.5430527758506498 + 51.87377121150501 + 62.36813868970528 + 53.41759414375864 + 59.98836798134744 + 35 + 6047.409481286305 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.5404253949175911,51.87984317552653,73.81262799233804 + + + + The Diamond Jubilee Maternity Unit + + -0.2124631480823957 + 51.92494721624239 + 104.0976233919343 + 52.9758961558414 + 59.95105134000257 + 35 + 1253.18674576105 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2129362336881956,51.92518764307876,110.0953336152518 + + + + Lister Hospital + + -0.212468574646324 + 51.92494469212421 + 104.3672773546513 + 52.97589188408732 + 59.9510471482962 + 35 + 1252.648283772724 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2135874989268621,51.92479263064346,101.8568048294726 + + + + HUC - Out of Hours GP + + -0.2128663374478001 + 51.92409839224334 + 103.9704651502259 + 52.97090875999339 + 59.94615536733049 + 35 + 624.1757174913073 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2124606678525842,51.92399879325587,104.0006496808524 + + + + Lister Hospital Emergency Department + + -0.2130003658019952 + 51.92379570577413 + 103.6350906758858 + 52.96867367002447 + 59.94400554001695 + 35 + 347.9761926599167 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2131164264773755,51.92347331413398,105.8779680833839 + + + + Nuffield Health The Holly Hospital + + 0.04585464223887392 + 51.6273689474134 + 38.71012647809278 + 52.6782196690201 + 51.39213189060273 + 35 + 7140.686088680523 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.03206290779532616,51.62442607065198,89.33019685902229 + + + + Queen's Hospital + + 0.1776221298435821 + 51.568919431133 + 18.68235898810621 + 52.70128481440929 + 51.35174310452052 + 35 + 1389.46064643198 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1807244269402526,51.56881358641575,12.94033315619186 + + + + Westland Medical Centre + + 0.2228178699336936 + 51.56316393681531 + 24.91386746893415 + 52.71510149753455 + 51.34380426939081 + 35 + 259.002024237634 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.222502152998362,51.56324992662208,36.43244775473649 + + + + St Helier Hospital + + -0.1836714323780464 + 51.37943893083443 + 64.97684684371181 + 52.53141226490936 + 51.3474330441067 + 35 + 775.7306094201341 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1840303861177935,51.38066504383517,54.62768807727091 + + + + Royal Marsden Hospital Sutton + + -0.1822717128616835 + 51.35589791498172 + 82.72412170132267 + 0 + 0 + 35 + 10106.34484948707 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1905873927941104,51.34350718522376,113.8340941248334 + + + + Purley War Memorial Hospital + + -0.1255512268054504 + 51.34715829880357 + 94.09292593156277 + 0 + 0 + 35 + 7615.273579903878 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.114544072907744,51.34062051573004,67.32324151583683 + + + + Croydon University Hospital + + -0.1282538571809755 + 51.36920404406935 + 33.23487247684645 + 0 + 0 + 35 + 14722.70630323096 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1102925394917569,51.389918395302,41.05019751627281 + + + + Shirley Oaks Hospital + + -0.0616817930399749 + 51.38073877031137 + 60.35530623298428 + 0 + 0 + 35 + 3182.032219815302 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.05634685139080654,51.38221664329148,60.984781076469 + + + + Croydon Ambulance Station + + -0.06251225601590193 + 51.38016865443452 + 60.88740413407257 + 0 + 0 + 35 + 4138.098180682864 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.06024907709478369,51.37797845256939,66.88672959253627 + + + + The Sloane Hospital + + -0.003827308058029777 + 51.408502944809 + 53.75774730066906 + 0 + 0 + 35 + 4994.659184503835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.004566234546706421,51.40833204621094,52.72717876895458 + + + + Thorridon Road Medical Practice + + 0.02233089355464069 + 51.42543834363784 + 62.51135261638856 + 0 + 0 + 35 + 7836.865521763684 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.002054664159771846,51.440107077768,40.88826480158826 + + + + Oakview Family Practice + + 0.02130458356131015 + 51.43560043559513 + 50.07093654013592 + 0 + 0 + 35 + 8053.896853752667 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.008003161007248405,51.42990810684785,61.19208890472149 + + + + The Links Medical Practice + + 0.02130458356131015 + 51.43560043559513 + 50.07093654013592 + 0 + 0 + 35 + 8053.896853752667 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.04154414921016782,51.42766668244509,70.41641735557513 + + + + Sidcup Medical Centre + + 0.1092621727262832 + 51.44660865553494 + 31.79733927167157 + 0 + 0 + 35 + 8072.170443929499 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.105179783005751,51.44519015710028,31.82578746927528 + + + + Lyndhurst Medical Centre + + 0.1562897017726139 + 51.45661682961929 + 52.3107859491431 + 0 + 0 + 35 + 6261.262700851077 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.158829036674426,51.46116796457344,56.48601887654782 + + + + Erith and District Hospital + + 0.1646645982058437 + 51.47784355884365 + 39.09017403376667 + 0 + 0 + 35 + 4587.136169738369 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1673704454554059,51.47691812682567,43.98073424517573 + + + + Berwick Surgery + + 0.217899522818934 + 51.52204207630847 + 5.612937055866576 + 0 + 0 + 35 + 5203.539418349974 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.2141959818805272,51.52672713573709,11.57048005941898 + + + + Orsett Hospital + + 0.3664475623693453 + 51.5150045658266 + 14.61465933947184 + 0 + 0 + 35 + 5170.4788906232 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.3659851248043444,51.50986627410659,29.45152708742405 + + + + King George Hospital + + 0.1131400861304566 + 51.6036926176623 + 34.77471337249119 + 0 + 0 + 35 + 20172.14336291654 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1115406191337875,51.58020252921018,28.66285418751985 + + + + Amersham Hospital + + -0.6342053682990934 + 51.66509123897674 + 149.5720681058467 + 0 + 0 + 35 + 13772.91424037889 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.6219161072258006,51.66248155450033,104.6373374748187 + + + + Wexham Park Hospital + + -0.5762301074521392 + 51.53097676898582 + 39.26576307603242 + 0 + 0 + 35 + 10412.39299668116 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.5743065471308129,51.53198531659324,40.26845657665874 + + + + Hillingdon Hospital + + -0.4679403951494432 + 51.52584487861473 + 27.21307323300876 + 0 + 0 + 35 + 5016.97494800901 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.461237980769241,51.52520706750175,42.05823445105383 + + + + Chepstow Garden Medical Centre + + -0.3743511306119784 + 51.51983377508201 + 35.59607571201144 + 0 + 0 + 35 + 2047.961368760734 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3751830368179809,51.51764542612705,36.24763743995023 + + + + Jubilee Garden Medical Centre + + -0.3743511306119784 + 51.51983377508201 + 35.59607571201144 + 0 + 0 + 35 + 2047.961368760734 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3692423185887139,51.52124238610774,45.62938978512876 + + + + Shackleton Care + + -0.3762781686906969 + 51.51334896492931 + 26.6306137555698 + 0 + 0 + 35 + 613.3674930026609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.376576046380791,51.51400575461064,33.02093250534271 + + + + Lady Margaret Road Medical Centre + + -0.3762781686906969 + 51.51334896492931 + 26.6306137555698 + 0 + 0 + 35 + 613.3674930026609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3756876450724222,51.51322413221729,31.79962578264546 + + + + Ealing Hospital + + -0.3475974152001449 + 51.50816120422 + 26.53977458429974 + 0 + 0 + 35 + 1159.575944942044 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3465248149688316,51.50751868302849,10.97122643493213 + + + + Northwick Park Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3202882107130534,51.57532030752736,59.37782426476122 + + + + The Clementine Churchil Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3321707589285809,51.5650667535168,85.33377956359243 + + + + Edgware Community Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2710066678387879,51.60647115563065,47.77192794539427 + + + + North Middlesex University Hospital + + -0.09826342248914433 + 51.59887136142904 + 16.29834450224789 + 0 + 0 + 35 + 17954.37715320149 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.07348212287029532,51.61310744874702,16.34704237642337 + + + + Whipps Cross University Hospital + + -0.00318 + 51.57791 + 21.12856769576882 + 0 + 0 + 35 + 23339.02225369122 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + -0.03464309208118022,51.84623406486086,26.76480826700025 + + + + Chase Farm Hospital + + -0.09445976388827715 + 51.64827324649203 + 45.18742363056923 + 0 + 0 + 35 + 20112.77904122835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1028073489011011,51.66689124911596,65.56377192754866 + + + + The Cavell Hospital + + -0.09445976388827715 + 51.64827324649203 + 45.18742363056923 + 0 + 0 + 35 + 20112.77904122835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1004158897945784,51.65899468845168,65.56296912431105 + + +
+ + Vale Drive Primary Care Centre + + -0.1968710123449446 + 51.65064622007617 + 119.0496245502007 + 33.95610494125125 + 51.61511454086038 + 35 + 783.3107969355478 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1951169862852115,51.6497469421364,106.8249971668427 + + + + Broomfield Hospital + + 0.4658531148979139 + 51.7730741281356 + 53.91494881236988 + -2.457264969088007 + 0.8143978401954622 + 35 + 962.681589408021 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4661826118043533,51.77432116677244,62.15314977461038 + + + + Colchester Hospital + + 0.8977119812889867 + 51.897302757459 + 9.164679933150786 + 8.311353741625599e-08 + 5.69202850576525 + 35 + 7908.249561059058 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.8989016354739056,51.90985612864645,52.129981717103 + + + + Oaks Hospital + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + 0.8950007512019129,51.90631333268821,40.85532839312136 + + + + Primary Care Centre + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.9020700978708827,51.90668078352024,41.05316266193498 + + + + Springfield Hospital + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4847439958367916,51.75341033368938,37.20936407432514 + + + + Chelmsford Ambulance Station + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.486090691535023,51.75595480607432,30.37470452823173 + + + + Chelmsford Medical Partnership + + 0.490010317636238 + 51.74347030470852 + 41.0383120629581 + 8.400205233656506e-08 + 5.686681664178874 + 35 + 1906.346236672543 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4851154704670301,51.74716663521045,42.72730373314561 + + + + St Margaret's Hospital + + 0.1249376747268771 + 51.7056521315599 + 114.9181035087347 + 8.43019173841836e-08 + 5.69293409158565 + 35 + 8924.934771554545 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1237980769230785,51.70491929118251,115.6421697734014 + + + + Princess Alexander Hospital + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.08539556146978197,51.76952006829818,64.14747173662603 + + + + Princess Alexandra Hospital Emergency Dep + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.0868200246143358,51.77176739550571,69.79413382101708 + + + + The Hamilton Practice + + 0.09407606608095032 + 51.76102983091437 + 62.82177510919995 + 8.385446841027487e-08 + 5.687801445829821 + 35 + 3163.337353592506 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1129865782056449,51.75607366423915,73.36016156645285 + + + + Rivers Hospital + + 0.1269921237352722 + 51.80593562347006 + 76.90405189061812 + 8.35673695662816e-08 + 5.690141647479414 + 35 + 5790.285723345587 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1356597399818305,51.80818175439256,68.28605103152285 + + + + Southend University Hospital + + 0.686807362759585 + 51.55442186733111 + 38.34213267175858 + 53.39226911898427 + 59.94270415751299 + 35 + 180.7781594831977 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6877328222924616,51.55385927682786,40.11469741632487 + + + + St Albans City Hospital + + -0.3457139310618307 + 51.74319846245394 + 91.24766614316273 + 53.11981616282007 + 60.0613137551813 + 35 + 15419.13049176335 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3435461023351755,51.76043771309943,110.8324392548333 + + + + Hemel Hempsteam Hospital + + -0.4695075770543722 + 51.75069927539609 + 108.933477195889 + 52.91641952113871 + 59.94724979383651 + 35 + 764.7829484937392 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.4691092344696746,51.7516592203038,124.3043795309861 + + + + Stoke Mandeville Hospital + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8061987654715064,51.81044035125617,88.5627270743543 + + + + Stoke Mandeville Hospital Emergency + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8014090401785613,51.79736510287374,90.28124226004431 + + + + Waddesdon Wing Maternity Outpatients Antenatal + + -0.8021384379958951 + 51.79719545416784 + 90.92761652804441 + 52.81887036614162 + 51.34717542765949 + 35 + 739.049740673363 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8000927812905456,51.79724865426316,92.9616022829897 + + + + Phoenix Hospital Chelmsford + + 0.4693273523125319 + 51.71077841110404 + 67.2959564377251 + 34.37350968852617 + 51.66017289287989 + 35 + 7175.670542574953 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.5035843063186717,51.70695925794588,36.53239001018486 + + + + Chelmsford & Essex Hospita + + 0.4723566742305252 + 51.73189932639333 + 23.32981638330202 + 34.3362298903192 + 51.61801892945288 + 35 + 1195.337775519001 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4710096422132502,51.73092405457083,35.83657572852461 + + + + Stapleford House + + 0.4683472433281599 + 51.72932847109089 + 35.19844820185988 + 34.33482353995927 + 51.61768196773221 + 35 + 1147.535923757823 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4663354223901122,51.72999144599144,31.24564959711314 + + + + Whitley House Surgery + + 0.4574225151539602 + 51.72370337607269 + 53.76763205449836 + 34.32854201256372 + 51.62043206484431 + 35 + 1537.691036219039 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.456043285327947,51.72642076891589,48.45157475308184 + + + + The Writtle Surgery + + 0.4307278930562286 + 51.72920902048297 + 41.74006982584603 + 34.31337571691095 + 51.62858416804543 + 35 + 2694.211246461491 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.42651098901098,51.73261225563316,35.54494197837538 + + + + Barnet Hospital + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.213735727163469,51.6508233199992,115.5282869113015 + + + + Barnet Hospital Emergency Department + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2161576826493854,51.65055615262246,125.5996772205984 + + + + Hadley Wood Hospital + + -0.1981320364942063 + 51.65279534597052 + 125.0634923173999 + 33.95924878558147 + 51.61956884043195 + 35 + 1415.242666276609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1969832535628527,51.65449483924015,112.7852073322038 + + + + Medstar Clinic + + -0.1504930494292478 + 51.61739661253369 + 52.08032173071229 + 33.97802065777326 + 51.61813033259048 + 35 + 1211.147772304685 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1514262105082491,51.61601546985334,60.94665359539616 + + + + Lordship Lane Primary Care Centre + + -0.08535541171442618 + 51.59570416495118 + 14.86720000060767 + 34.00430616452158 + 51.62460473348132 + 35 + 2129.647572840331 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.0805596990899683,51.5972710103994,21.36209261262719 + + + + Cheshunt Community Hospital + + -0.03335 + 51.6996 + 28.21933806852695 + 34.05244126896145 + 51.63689768466914 + 35 + 3873.625454957946 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + -0.03848996120356829,1,25.78451729971917 + + +
+
+
diff --git a/convert_KML_to_TSP.py b/convert_KML_to_TSP.py new file mode 100644 index 0000000000..a3676eaefc --- /dev/null +++ b/convert_KML_to_TSP.py @@ -0,0 +1,38 @@ +import xml.etree.ElementTree as ET + +def parse_kml(kml_file): + tree = ET.parse(kml_file) + root = tree.getroot() + namespace = {'kml': 'http://www.opengis.net/kml/2.2'} + coordinates = [] + + for placemark in root.findall('.//kml:Placemark', namespace): + coords = placemark.find('.//kml:coordinates', namespace).text.strip() + for coord in coords.split(): + lon, lat, _ = map(float, coord.split(',')) + coordinates.append((lat, lon)) + + return coordinates + +def convert_to_tsp(coordinates, tsp_file): + with open(tsp_file, 'w') as f: + f.write(f"NAME: example\n") + f.write(f"TYPE: TSP\n") + f.write(f"DIMENSION: {len(coordinates)}\n") + f.write(f"EDGE_WEIGHT_TYPE: EUC_2D\n") + f.write(f"NODE_COORD_SECTION\n") + + for i, (lat, lon) in enumerate(coordinates, start=1): + f.write(f"{i} {lat} {lon}\n") + + f.write(f"EOF\n") + +# Main execution +kml_file = '/home/dell/ALNS/Destinations.kml' +tsp_file = '/home/dell/ALNS/Destinations.tsp' + +coordinates = parse_kml(kml_file) +convert_to_tsp(coordinates, tsp_file) + +print(f"Converted {len(coordinates)} points from {kml_file} to {tsp_file}") + diff --git a/mavproxy_kml.py b/mavproxy_kml.py new file mode 100644 index 0000000000..583cbb2114 --- /dev/null +++ b/mavproxy_kml.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import pexpect +import time + +# Define the MAVProxy command +mavproxy_cmd = "mavproxy.py --master=udpin:127.0.0.1:14550 --console --map --out=udpout:127.0.0.1:14552" + +# Start MAVProxy +child = pexpect.spawn(mavproxy_cmd) + +# Wait for MAVProxy to load +child.expect("Received", timeout=60) + +# Load the kmlread module +child.sendline("module load kmlread") + +# Wait for the module to load +time.sleep(2) + +# Load the KML file +child.sendline("kml load /home/dell/Essex_Hospitals_NoFlyZones.kml") + +# Give some time for the KML to load and process +time.sleep(5) + +# Optionally, you can add more commands here, e.g., to toggle visibility or create fences + +# Interact with MAVProxy console +child.interact() + From 0e4d7ab860969a380d8c31f6865ada6397651c7b Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sat, 6 Jul 2024 23:11:45 +0100 Subject: [PATCH 17/33] Add files via upload --- Cap_Veh_Routing.py | 312 + Destinations.kml | 639 ++ Destinations.tsp | 35 + Fences.kml | 21470 ++++++++++++++++++++++++++++++++++++ Fences.tsp | 20615 ++++++++++++++++++++++++++++++++++ Trav_SalMan.py | 195 + Trav_SalMan1.py | 160 + Trav_SalMan1_hospitals.py | 231 + 8 files changed, 43657 insertions(+) create mode 100644 Cap_Veh_Routing.py create mode 100644 Destinations.kml create mode 100644 Destinations.tsp create mode 100644 Fences.kml create mode 100644 Fences.tsp create mode 100644 Trav_SalMan.py create mode 100644 Trav_SalMan1.py create mode 100644 Trav_SalMan1_hospitals.py diff --git a/Cap_Veh_Routing.py b/Cap_Veh_Routing.py new file mode 100644 index 0000000000..65673ff158 --- /dev/null +++ b/Cap_Veh_Routing.py @@ -0,0 +1,312 @@ +import copy +from types import SimpleNamespace + +import vrplib +import matplotlib +import matplotlib.pyplot as plt +import numpy as np +import numpy.random as rnd + +from alns import ALNS +from alns.accept import RecordToRecordTravel +from alns.select import RouletteWheel +from alns.stop import MaxRuntime + +# Set matplotlib to display plots inline in Jupyter Notebook or similar environments +# matplotlib inline + +SEED = 1234 + +# Function to plot CVRP solution +def plot_solution(solution, name="CVRP solution"): + """ + Plot the routes of the passed-in solution. + """ + fig, ax = plt.subplots(figsize=(12, 6)) # Adjust figsize as needed + cmap = matplotlib.cm.rainbow(np.linspace(0, 1, len(solution.routes))) + + for idx, route in enumerate(solution.routes): + ax.plot( + [data["node_coord"][loc][0] for loc in [0] + route + [0]], + [data["node_coord"][loc][1] for loc in [0] + route + [0]], + color=cmap[idx], + marker='.' + ) + + # Plot the depot + kwargs = dict(label="Depot", zorder=3, marker="*", s=750) + ax.scatter(*data["node_coord"][0], c="tab:red", **kwargs) + + ax.set_title(f"{name}\n Total distance: {solution.cost}") + ax.set_xlabel("X-coordinate") + ax.set_ylabel("Y-coordinate") + ax.legend(frameon=False, ncol=3) + +# Initialize VRP data and best known solution (bks) +data = vrplib.read_instance('/home/dell/ALNS/examples/data/ORTEC-n242-k12.vrp') +bks = SimpleNamespace(**vrplib.read_solution('/home/dell/ALNS/examples/data/ORTEC-n242-k12.sol')) + +# CVRP state class definition +class CvrpState: + """ + Solution state for CVRP. It has two data members, routes and unassigned. + Routes is a list of list of integers, where each inner list corresponds to + a single route denoting the sequence of customers to be visited. A route + does not contain the start and end depot. Unassigned is a list of integers, + each integer representing an unassigned customer. + """ + + def __init__(self, routes, unassigned=None): + self.routes = routes + self.unassigned = unassigned if unassigned is not None else [] + + def copy(self): + return CvrpState(copy.deepcopy(self.routes), self.unassigned.copy()) + + def objective(self): + """ + Computes the total route costs. + """ + return sum(route_cost(route) for route in self.routes) + + @property + def cost(self): + """ + Alias for objective method. Used for plotting. + """ + return self.objective() + + def find_route(self, customer): + """ + Return the route that contains the passed-in customer. + """ + for route in self.routes: + if customer in route: + return route + + raise ValueError(f"Solution does not contain customer {customer}.") + +def route_cost(route): + distances = data["edge_weight"] + tour = [0] + route + [0] + + return sum(distances[tour[idx]][tour[idx + 1]] + for idx in range(len(tour) - 1)) + +# Define destroy operators +degree_of_destruction = 0.05 +customers_to_remove = int((data["dimension"] - 1) * degree_of_destruction) + +def random_removal(state, rnd_state): + """ + Removes a number of randomly selected customers from the passed-in solution. + """ + destroyed = state.copy() + + for customer in rnd_state.choice( + range(1, data["dimension"]), customers_to_remove, replace=False + ): + destroyed.unassigned.append(customer) + route = destroyed.find_route(customer) + route.remove(customer) + + return remove_empty_routes(destroyed) + +def remove_empty_routes(state): + """ + Remove empty routes after applying the destroy operator. + """ + state.routes = [route for route in state.routes if len(route) != 0] + return state + +# Define repair operator +def greedy_repair(state, rnd_state): + """ + Inserts the unassigned customers in the best route. If there are no + feasible insertions, then a new route is created. + """ + rnd_state.shuffle(state.unassigned) + + while len(state.unassigned) != 0: + customer = state.unassigned.pop() + route, idx = best_insert(customer, state) + + if route is not None: + route.insert(idx, customer) + else: + state.routes.append([customer]) + + return state + +def best_insert(customer, state): + """ + Finds the best feasible route and insertion idx for the customer. + Return (None, None) if no feasible route insertions are found. + """ + best_cost, best_route, best_idx = None, None, None + + for route in state.routes: + for idx in range(len(route) + 1): + if can_insert(customer, route): + cost = insert_cost(customer, route, idx) + + if best_cost is None or cost < best_cost: + best_cost, best_route, best_idx = cost, route, idx + + return best_route, best_idx + +def can_insert(customer, route): + """ + Checks if inserting customer does not exceed vehicle capacity. + """ + total = data["demand"][route].sum() + data["demand"][customer] + return total <= data["capacity"] + +def insert_cost(customer, route, idx): + """ + Computes the insertion cost for inserting customer in route at idx. + """ + dist = data["edge_weight"] + pred = 0 if idx == 0 else route[idx - 1] + succ = 0 if idx == len(route) else route[idx] + + # Increase in cost of adding customer, minus cost of removing old edge + return dist[pred][customer] + dist[customer][succ] - dist[pred][succ] + +def neighbors(customer): + """ + Return the nearest neighbors of the customer, excluding the depot. + """ + locations = np.argsort(data["edge_weight"][customer]) + return locations[locations != 0] + +def nearest_neighbor(): + """ + Build a solution by iteratively constructing routes, where the nearest + customer is added until the route has met the vehicle capacity limit. + """ + routes = [] + unvisited = set(range(1, data["dimension"])) + + while unvisited: + route = [0] # Start at the depot + route_demands = 0 + + while unvisited: + # Add the nearest unvisited customer to the route till max capacity + current = route[-1] + nearest = [nb for nb in neighbors(current) if nb in unvisited][0] + + if route_demands + data["demand"][nearest] > data["capacity"]: + break + + route.append(nearest) + unvisited.remove(nearest) + route_demands += data["demand"][nearest] + + customers = route[1:] # Remove the depot + routes.append(customers) + + return CvrpState(routes) + +# Plotting the nearest neighbor solution +plot_solution(nearest_neighbor(), 'Nearest neighbor solution') + +# Initialize ALNS and run for the first scenario +alns = ALNS(rnd.RandomState(SEED)) +alns.add_destroy_operator(random_removal) +alns.add_repair_operator(greedy_repair) +init = nearest_neighbor() +select = RouletteWheel([25, 5, 1, 0], 0.8, 1, 1) +accept = RecordToRecordTravel.autofit(init.objective(), 0.02, 0, 9000) +stop = MaxRuntime(60) + +result = alns.iterate(init, select, accept, stop) +solution = result.best_state +objective = solution.objective() +pct_diff = 100 * (objective - bks.cost) / bks.cost + +print(f"Best heuristic objective is {objective}.") +print(f"This is {pct_diff:.1f}% worse than the optimal solution, which is {bks.cost}.") + +# Plotting ALNS results for the first scenario +fig1, ax1 = plt.subplots(figsize=(12, 6)) +result.plot_objectives(ax=ax1) + +# Adding string removal operator to ALNS +MAX_STRING_REMOVALS = 2 +MAX_STRING_SIZE = 12 + +def string_removal(state, rnd_state): + """ + Remove partial routes around a randomly chosen customer. + """ + destroyed = state.copy() + + avg_route_size = int(np.mean([len(route) for route in state.routes])) + max_string_size = max(MAX_STRING_SIZE, avg_route_size) + max_string_removals = min(len(state.routes), MAX_STRING_REMOVALS) + + destroyed_routes = [] + center = rnd_state.randint(1, data["dimension"]) + + for customer in neighbors(center): + if len(destroyed_routes) >= max_string_removals: + break + + if customer in destroyed.unassigned: + continue + + route = destroyed.find_route(customer) + if route in destroyed_routes: + continue + + customers = remove_string(route, customer, max_string_size, rnd_state) + destroyed.unassigned.extend(customers) + destroyed_routes.append(route) + + return destroyed + +def remove_string(route, cust, max_string_size, rnd_state): + """ + Remove a string that contains the passed-in customer. + """ + # Find consecutive indices to remove that contain the customer + size = rnd_state.randint(1, min(len(route), max_string_size) + 1) + start = route.index(cust) - rnd_state.randint(size) + idcs = [idx % len(route) for idx in range(start, start + size)] + + # Remove indices in descending order + removed_customers = [] + for idx in sorted(idcs, reverse=True): + removed_customers.append(route.pop(idx)) + + return removed_customers + +# Initialize ALNS and run for the second scenario with string removal +alns = ALNS(rnd.RandomState(SEED)) +alns.add_destroy_operator(string_removal) +alns.add_repair_operator(greedy_repair) +init = nearest_neighbor() +select = RouletteWheel([25, 5, 1, 0], 0.8, 1, 1) +accept = RecordToRecordTravel.autofit(init.objective(), 0.02, 0, 6000) +stop = MaxRuntime(60) + +result = alns.iterate(init, select, accept, stop) +solution = result.best_state +objective = solution.objective() +pct_diff = 100 * (objective - bks.cost) / bks.cost + +print(f"Best heuristic objective is {objective}.") +print(f"This is {pct_diff:.1f}% worse than the optimal solution, which is {bks.cost}.") + +# Plotting ALNS results for the second scenario with string removal +fig2, ax2 = plt.subplots(figsize=(12, 6)) +result.plot_objectives(ax=ax2) + +# Plotting the final solution with string removals +plot_solution(solution, 'String removals') + +# Display all plots alongside each other +plt.show() + diff --git a/Destinations.kml b/Destinations.kml new file mode 100644 index 0000000000..ae166995dc --- /dev/null +++ b/Destinations.kml @@ -0,0 +1,639 @@ + + + + NATS AIM on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.
+ The content of this file is not guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free.]]>
+ + 2024-06-13 + 2024-06-13 + + + + + + + + + + normal + #__managed_style_14A059B9A031BF14491C + + + highlight + #__managed_style_071CBFDE2F31BF14491D + + + + + + + + + + + normal + #__managed_style_1DF75EF5A831BF144915 + + + highlight + #__managed_style_2EFD52E0E431BF144915 + + + + Destinations + 1 + + Vale Drive Primary Care Centre + + -0.1968710123449446 + 51.65064622007617 + 119.0496245502007 + 33.95610494125125 + 51.61511454086038 + 35 + 783.3107969355478 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.1951169862852115,51.6497469421364,106.8249971668427 + + + + Broomfield Hospital + + 0.4658531148979139 + 51.7730741281356 + 53.91494881236988 + -2.457264969088007 + 0.8143978401954622 + 35 + 962.681589408021 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4661826118043533,51.77432116677244,62.15314977461038 + + + + Colchester Hospital + + 0.8977119812889867 + 51.897302757459 + 9.164679933150786 + 8.311353741625599e-08 + 5.69202850576525 + 35 + 7908.249561059058 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.8989016354739056,51.90985612864645,52.129981717103 + + + + Oaks Hospital + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.8950007512019129,51.90631333268821,40.85532839312136 + + + + Primary Care Centre + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.9020700978708827,51.90668078352024,41.05316266193498 + + + + Springfield Hospital + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4847439958367916,51.75341033368938,37.20936407432514 + + + + Chelmsford Ambulance Station + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4860906915350229,51.75595480607432,30.37470452823173 + + + + Chelmsford Medical Partnership + + 0.490010317636238 + 51.74347030470852 + 41.0383120629581 + 8.400205233656506e-08 + 5.686681664178874 + 35 + 1906.346236672543 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4851154704670301,51.74716663521045,42.72730373314561 + + + + St Margaret's Hospital + + 0.1249376747268771 + 51.7056521315599 + 114.9181035087347 + 8.43019173841836e-08 + 5.69293409158565 + 35 + 8924.934771554545 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.1237980769230785,51.70491929118251,115.6421697734014 + + + + Princess Alexander Hospital + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.08539556146978197,51.76952006829818,64.14747173662603 + + + + Princess Alexandra Hospital Emergency Dep + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.0868200246143358,51.77176739550571,69.79413382101708 + + + + The Hamilton Practice + + 0.09407606608095032 + 51.76102983091437 + 62.82177510919995 + 8.385446841027487e-08 + 5.687801445829821 + 35 + 3163.337353592506 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.1129865782056449,51.75607366423915,73.36016156645285 + + + + Rivers Hospital + + 0.1269921237352722 + 51.80593562347006 + 76.90405189061812 + 8.35673695662816e-08 + 5.690141647479414 + 35 + 5790.285723345587 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.1356597399818305,51.80818175439255,68.28605103152285 + + + + Southend University Hospital + + 0.686807362759585 + 51.55442186733111 + 38.34213267175858 + 53.39226911898427 + 59.94270415751299 + 35 + 180.7781594831977 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.6877328222924616,51.55385927682786,40.11469741632487 + + + + St Albans City Hospital + + -0.3457139310618307 + 51.74319846245394 + 91.24766614316273 + 53.11981616282007 + 60.0613137551813 + 35 + 15419.13049176335 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.3435461023351755,51.76043771309943,110.8324392548333 + + + + Hemel Hempsteam Hospital + + -0.4695075770543722 + 51.75069927539609 + 108.933477195889 + 52.91641952113871 + 59.94724979383651 + 35 + 764.7829484937392 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.4691092344696746,51.7516592203038,124.3043795309861 + + + + Stoke Mandeville Hospital + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.8061987654715064,51.81044035125617,88.5627270743543 + + + + Stoke Mandeville Hospital Emergency + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.8014090401785613,51.79736510287374,90.28124226004431 + + + + Waddesdon Wing Maternity Outpatients Antenatal + + -0.8021384379958951 + 51.79719545416784 + 90.92761652804441 + 52.81887036614162 + 51.34717542765949 + 35 + 739.049740673363 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.8000927812905456,51.79724865426316,92.9616022829897 + + + + Phoenix Hospital Chelmsford + + 0.4693273523125319 + 51.71077841110404 + 67.2959564377251 + 34.37350968852617 + 51.66017289287989 + 35 + 7175.670542574953 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.5035843063186717,51.70695925794588,36.53239001018486 + + + + Chelmsford & Essex Hospita + + 0.4723566742305252 + 51.73189932639333 + 23.32981638330202 + 34.3362298903192 + 51.61801892945288 + 35 + 1195.337775519001 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4710096422132502,51.73092405457083,35.83657572852461 + + + + Stapleford House + + 0.4683472433281599 + 51.72932847109089 + 35.19844820185988 + 34.33482353995927 + 51.61768196773221 + 35 + 1147.535923757823 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.4663354223901122,51.72999144599143,31.24564959711314 + + + + Whitley House Surgery + + 0.4574225151539602 + 51.72370337607269 + 53.76763205449836 + 34.32854201256372 + 51.62043206484431 + 35 + 1537.691036219039 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.456043285327947,51.72642076891589,48.45157475308184 + + + + The Writtle Surgery + + 0.4307278930562286 + 51.72920902048297 + 41.74006982584603 + 34.31337571691095 + 51.62858416804543 + 35 + 2694.211246461491 + absolute + + #__managed_style_06A96EF91C31BF144915 + + 0.42651098901098,51.73261225563316,35.54494197837538 + + + + Barnet Hospital + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.213735727163469,51.6508233199992,115.5282869113015 + + + + Barnet Hospital Emergency Department + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.2161576826493854,51.65055615262246,125.5996772205984 + + + + Hadley Wood Hospital + + -0.1981320364942063 + 51.65279534597052 + 125.0634923173999 + 33.95924878558147 + 51.61956884043195 + 35 + 1415.242666276609 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.1969832535628527,51.65449483924015,112.7852073322038 + + + + Medstar Clinic + + -0.1504930494292478 + 51.61739661253369 + 52.08032173071229 + 33.97802065777326 + 51.61813033259048 + 35 + 1211.147772304685 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.1514262105082491,51.61601546985334,60.94665359539616 + + + + Lordship Lane Primary Care Centre + + -0.08535541171442618 + 51.59570416495118 + 14.86720000060767 + 34.00430616452158 + 51.62460473348132 + 35 + 2129.647572840331 + absolute + + #__managed_style_06A96EF91C31BF144915 + + -0.0805596990899683,51.5972710103994,21.36209261262719 + + + + Cheshunt Community Hospital + + -0.03335 + 51.6996 + 28.21933806852695 + 34.05244126896145 + 51.63689768466914 + 35 + 3873.625454957946 + absolute + + #__managed_style_09B76AF35231BF14491C + + -0.03848996120356829,1,25.78451729971917 + + + +
+
diff --git a/Destinations.tsp b/Destinations.tsp new file mode 100644 index 0000000000..47c9f2d018 --- /dev/null +++ b/Destinations.tsp @@ -0,0 +1,35 @@ +NAME: example +TYPE: TSP +DIMENSION: 30 +EDGE_WEIGHT_TYPE: EUC_2D +NODE_COORD_SECTION +1 51.6497469421364 -0.1951169862852115 +2 51.77432116677244 0.4661826118043533 +3 51.90985612864645 0.8989016354739056 +4 51.90631333268821 0.8950007512019129 +5 51.90668078352024 0.9020700978708827 +6 51.75341033368938 0.4847439958367916 +7 51.75595480607432 0.4860906915350229 +8 51.74716663521045 0.4851154704670301 +9 51.70491929118251 0.1237980769230785 +10 51.76952006829818 0.08539556146978197 +11 51.77176739550571 0.0868200246143358 +12 51.75607366423915 0.1129865782056449 +13 51.80818175439255 0.1356597399818305 +14 51.55385927682786 0.6877328222924616 +15 51.76043771309943 -0.3435461023351755 +16 51.7516592203038 -0.4691092344696746 +17 51.81044035125617 -0.8061987654715064 +18 51.79736510287374 -0.8014090401785613 +19 51.79724865426316 -0.8000927812905456 +20 51.70695925794588 0.5035843063186717 +21 51.73092405457083 0.4710096422132502 +22 51.72999144599143 0.4663354223901122 +23 51.72642076891589 0.456043285327947 +24 51.73261225563316 0.42651098901098 +25 51.6508233199992 -0.213735727163469 +26 51.65055615262246 -0.2161576826493854 +27 51.65449483924015 -0.1969832535628527 +28 51.61601546985334 -0.1514262105082491 +29 51.5972710103994 -0.0805596990899683 +EOF diff --git a/Fences.kml b/Fences.kml new file mode 100644 index 0000000000..23d9caf817 --- /dev/null +++ b/Fences.kml @@ -0,0 +1,21470 @@ + + + + Created by <a href="/service/mailto:aissupervisor@nats.co.uk"> NATS AIM </a> on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.<br/> + The content of this file is <b> not</b> guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free. + + 2024-06-13T00:00:00Z + 2024-06-13T00:00:00Z + + + + + + + + + + + + + + + + + + normal + #asestyle + + + highlight + #highlightStyle + + + + + normal + #coastStyle + + + highlight + #highlightStyle + + + + + normal + #rdpstyle + + + highlight + #highlightStyle + + + + + normal + #rtestyle + + + highlight + #highlightStyle + + + + Airspaces + + Danger + + EGD001 TREVOSE HEAD + <table border="1" cellpadding="1" cellspacing="0" row_id="959" txt_name="TREVOSE HEAD"><tr><td>501918N 0053042W -<br/>502400N 0053900W -<br/>503200N 0053400W -<br/>503930N 0052400W -<br/>504300N 0051230W -<br/>503830N 0050430W -<br/>501918N 0053042W <br/>Upper limit: 1000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552415.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5116666667,50.3216666667,304.8 -5.075,50.6416666667,304.8 -5.2083333333,50.7166666667,304.8 -5.4,50.6583333333,304.8 -5.5666666667,50.5333333333,304.8 -5.65,50.4,304.8 -5.5116666667,50.3216666667,304.8 + + + + + + EGD003 PLYMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1246" txt_name="PLYMOUTH"><tr><td>501001N 0034740W -<br/>500339N 0033430W -<br/>494105N 0034912W -<br/>493719N 0040938W -<br/>501001N 0034740W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.7944444444,50.1669444444,6705.6 -4.1605555556,49.6219444444,6705.6 -3.82,49.6847222222,6705.6 -3.575,50.0608333333,6705.6 -3.7944444444,50.1669444444,6705.6 + + + + + + EGD004 PLYMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1625" txt_name="PLYMOUTH"><tr><td>500339N 0033430W -<br/>500103N 0032910W -<br/>494653N 0031655W -<br/>494105N 0034912W -<br/>500339N 0033430W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.575,50.0608333333,6705.6 -3.82,49.6847222222,6705.6 -3.2819444444,49.7813888889,6705.6 -3.4861111111,50.0175,6705.6 -3.575,50.0608333333,6705.6 + + + + + + EGD005A PREDANNACK + <table border="1" cellpadding="1" cellspacing="0" row_id="4315" txt_name="PREDANNACK"><tr><td>A circle, 3 NM radius, centred at 500007N 0051354W <br/>Upper limit: 8000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2317694444,50.0519840728,2438.4 -5.2382609639,50.0518087079,2438.4 -5.244706809,50.0512838469,2438.4 -5.2510616297,50.0504131826,2438.4 -5.2572807223,50.0492028405,2438.4 -5.2633203464,50.0476613353,2438.4 -5.2691380355,50.0457995106,2438.4 -5.2746928974,50.0436304617,2438.4 -5.2799459031,50.0411694431,2438.4 -5.2848601634,50.0384337598,2438.4 -5.2894011878,50.0354426457,2438.4 -5.2935371276,50.0322171262,2438.4 -5.2972389989,50.0287798704,2438.4 -5.3004808854,50.0251550305,2438.4 -5.3032401186,50.0213680712,2438.4 -5.3054974349,50.01744559,2438.4 -5.3072371079,50.0134151297,2438.4 -5.308447056,50.0093049843,2438.4 -5.3091189239,50.0051440001,2438.4 -5.3092481369,50.0009613725,2438.4 -5.3088339296,49.9967864416,2438.4 -5.3078793473,49.9926484858,2438.4 -5.3063912206,49.9885765165,2438.4 -5.3043801136,49.9845990758,2438.4 -5.3018602465,49.9807440358,2438.4 -5.2988493928,49.9770384047,2438.4 -5.2953687514,49.9735081377,2438.4 -5.2914427962,49.9701779565,2438.4 -5.2870991023,49.9670711763,2438.4 -5.2823681521,49.9642095444,2438.4 -5.2772831207,49.9616130881,2438.4 -5.2718796434,49.9592999758,2438.4 -5.2661955671,49.957286391,2438.4 -5.2602706859,49.9555864196,2438.4 -5.2541464643,49.9542119522,2438.4 -5.2478657491,49.9531726018,2438.4 -5.2414724716,49.9524756371,2438.4 -5.2350113432,49.952125932,2438.4 -5.2285275456,49.952125932,2438.4 -5.2220664173,49.9524756371,2438.4 -5.2156731398,49.9531726018,2438.4 -5.2093924246,49.9542119522,2438.4 -5.203268203,49.9555864196,2438.4 -5.1973433218,49.957286391,2438.4 -5.1916592454,49.9592999758,2438.4 -5.1862557682,49.9616130881,2438.4 -5.1811707367,49.9642095444,2438.4 -5.1764397866,49.9670711763,2438.4 -5.1720960927,49.9701779565,2438.4 -5.1681701375,49.9735081377,2438.4 -5.1646894961,49.9770384047,2438.4 -5.1616786423,49.9807440358,2438.4 -5.1591587753,49.9845990758,2438.4 -5.1571476683,49.9885765165,2438.4 -5.1556595416,49.9926484858,2438.4 -5.1547049593,49.9967864416,2438.4 -5.154290752,50.0009613725,2438.4 -5.154419965,50.0051440001,2438.4 -5.1550918329,50.0093049843,2438.4 -5.156301781,50.0134151297,2438.4 -5.158041454,50.01744559,2438.4 -5.1602987703,50.0213680712,2438.4 -5.1630580035,50.0251550305,2438.4 -5.16629989,50.0287798704,2438.4 -5.1700017613,50.0322171262,2438.4 -5.1741377011,50.0354426457,2438.4 -5.1786787255,50.0384337598,2438.4 -5.1835929857,50.0411694431,2438.4 -5.1888459915,50.0436304617,2438.4 -5.1944008533,50.0457995106,2438.4 -5.2002185425,50.0476613353,2438.4 -5.2062581666,50.0492028405,2438.4 -5.2124772592,50.0504131826,2438.4 -5.2188320799,50.0512838469,2438.4 -5.225277925,50.0518087079,2438.4 -5.2317694444,50.0519840728,2438.4 + + + + + + EGD005B PREDANNACK CORRIDOR + <table border="1" cellpadding="1" cellspacing="0" row_id="4314" txt_name="PREDANNACK CORRIDOR"><tr><td>500208N 0051722W -<br/>495818N 0052242W -<br/>495124N 0051200W -<br/>495629N 0050728W -<br/>495809N 0051024W thence clockwise by the arc of a circle radius 3 NM centred on 500007N 0051354W to -<br/>500208N 0051722W <br/>Upper limit: 8000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2893774722,50.0354596389,2438.4 -5.3783333333,49.9716666667,2438.4 -5.2,49.8566666667,2438.4 -5.1243299444,49.94131175,2438.4 -5.1732655,49.969289,2438.4 -5.1776868569,49.9662693871,2438.4 -5.1824813042,49.9634969443,2438.4 -5.1876157091,49.9609907962,2438.4 -5.1930546103,49.9587682276,2438.4 -5.198760463,49.9568445653,2438.4 -5.2046938963,49.9552330729,2438.4 -5.2108139835,49.9539448608,2438.4 -5.2170785222,49.9529888094,2438.4 -5.2234443235,49.9523715092,2438.4 -5.2298675064,49.952097215,2438.4 -5.2363037984,49.9521678175,2438.4 -5.2427088373,49.9525828301,2438.4 -5.2490384744,49.9533393922,2438.4 -5.2552490759,49.9544322888,2438.4 -5.2612978212,49.9558539861,2438.4 -5.2671429954,49.9575946829,2438.4 -5.2727442751,49.9596423778,2438.4 -5.2780630047,49.9619829511,2438.4 -5.2830624614,49.9646002613,2438.4 -5.2877081082,49.9674762558,2438.4 -5.2919678313,49.9705910944,2438.4 -5.2958121626,49.9739232851,2438.4 -5.2992144834,49.9774498319,2438.4 -5.3021512098,49.9811463922,2438.4 -5.3046019571,49.9849874443,2438.4 -5.3065496835,49.9889464626,2438.4 -5.3079808099,49.9929961005,2438.4 -5.3088853174,49.9971083784,2438.4 -5.30925682,50.0012548768,2438.4 -5.309092612,50.0054069326,2438.4 -5.3083936908,50.0095358368,2438.4 -5.3071647539,50.013613033,2438.4 -5.3054141696,50.0176103157,2438.4 -5.3031539236,50.0215000252,2438.4 -5.3003995384,50.0252552394,2438.4 -5.2971699697,50.0288499612,2438.4 -5.2934874772,50.0322592989,2438.4 -5.2893774722,50.0354596389,2438.4 + + + + + + EGD006A FALMOUTH BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1551" txt_name="FALMOUTH BAY"><tr><td>501244N 0044659W -<br/>500726N 0044228W -<br/>500000N 0045430W -<br/>500924N 0045430W -<br/>501244N 0044659W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.7830555556,50.2122222222,6705.6 -4.9083333333,50.1566666667,6705.6 -4.9083333333,50.0,6705.6 -4.7077777778,50.1238888889,6705.6 -4.7830555556,50.2122222222,6705.6 + + + + + + EGD006B FALMOUTH BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1550" txt_name="FALMOUTH BAY"><tr><td>495907N 0050506W -<br/>500500N 0045948W -<br/>500924N 0045430W -<br/>500000N 0045430W -<br/>495646N 0045634W -<br/>495907N 0050506W <br/>Upper limit: 8000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0849987222,49.9851711667,2438.4 -4.9428074167,49.9462036944,2438.4 -4.9083333333,50.0,2438.4 -4.9083333333,50.1566666667,2438.4 -4.9966666667,50.0833333333,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + + + EGD006C FALMOUTH BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="4334" txt_name="FALMOUTH BAY"><tr><td>495907N 0050506W -<br/>495124N 0051200W -<br/>495124N 0050000W -<br/>495646N 0045634W -<br/>495907N 0050506W <br/>Upper limit: 8000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0849987222,49.9851711667,2438.4 -5.2,49.8566666667,2438.4 -5.0,49.8566666667,2438.4 -4.9428074167,49.9462036944,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + + + EGD007A FOWEY + <table border="1" cellpadding="1" cellspacing="0" row_id="1249" txt_name="FOWEY"><tr><td>501801N 0043643W -<br/>501820N 0043152W -<br/>501857N 0042738W -<br/>501550N 0042458W -<br/>500922N 0044407W -<br/>501202N 0044623W -<br/>501801N 0043643W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6119444444,50.3002777778,6705.6 -4.7730555556,50.2005555556,6705.6 -4.7352777778,50.1561111111,6705.6 -4.4161111111,50.2638888889,6705.6 -4.4605555556,50.3158333333,6705.6 -4.5311111111,50.3055555556,6705.6 -4.6119444444,50.3002777778,6705.6 + + + + + + EGD007B FOWEY + <table border="1" cellpadding="1" cellspacing="0" row_id="1552" txt_name="FOWEY"><tr><td>501550N 0042458W -<br/>501342N 0042309W -<br/>500726N 0044228W -<br/>500922N 0044407W -<br/>501550N 0042458W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4161111111,50.2638888889,6705.6 -4.7352777778,50.1561111111,6705.6 -4.7077777778,50.1238888889,6705.6 -4.3858333333,50.2283333333,6705.6 -4.4161111111,50.2638888889,6705.6 + + + + + + EGD007C FOWEY INNER + <table border="1" cellpadding="1" cellspacing="0" row_id="1248" txt_name="FOWEY INNER"><tr><td>501733N 0044334W -<br/>501801N 0043643W -<br/>501202N 0044623W -<br/>501244N 0044659W -<br/>501414N 0044441W -<br/>501647N 0044447W -<br/>501733N 0044334W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards..<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.7261111111,50.2925,609.6 -4.7463888889,50.2797222222,609.6 -4.7447222222,50.2372222222,609.6 -4.7830555556,50.2122222222,609.6 -4.7730555556,50.2005555556,609.6 -4.6119444444,50.3002777778,609.6 -4.7261111111,50.2925,609.6 + + + + + + EGD008A PLYMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1251" txt_name="PLYMOUTH"><tr><td>495654N 0045629W -<br/>493715N 0041003W -<br/>492745N 0050000W -<br/>495124N 0050000W -<br/>495654N 0045629W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9413888889,49.9483333333,6705.6 -5.0,49.8566666667,6705.6 -5.0,49.4625,6705.6 -4.1675,49.6208333333,6705.6 -4.9413888889,49.9483333333,6705.6 + + + + + + EGD008B PLYMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1252" txt_name="PLYMOUTH"><tr><td>494740N 0043430W -<br/>494438N 0040446W -<br/>493719N 0040938W -<br/>493715N 0041003W -<br/>494740N 0043430W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.575,49.7944444444,6705.6 -4.1675,49.6208333333,6705.6 -4.1605555556,49.6219444444,6705.6 -4.0794444444,49.7438888889,6705.6 -4.575,49.7944444444,6705.6 + + + + + + EGD008C PLYMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1250" txt_name="PLYMOUTH"><tr><td>501140N 0042931W thence anti-clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to<br/>500623N 0035008W -<br/>494438N 0040446W -<br/>494740N 0043430W -<br/>495654N 0045629W -<br/>500000N 0045430W -<br/>500726N 0044228W -<br/>501140N 0042931W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit 22000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4919444444,50.1944444444,16764.0 -4.7077777778,50.1238888889,16764.0 -4.9083333333,50.0,16764.0 -4.9413888889,49.9483333333,16764.0 -4.575,49.7944444444,16764.0 -4.0794444444,49.7438888889,16764.0 -3.8355555556,50.1063888889,16764.0 -3.8477298237,50.1003226175,16764.0 -3.8600996985,50.094429589,16764.0 -3.8727887629,50.0888258225,16764.0 -3.8857806495,50.0835184994,16764.0 -3.8990586201,50.0785144188,16764.0 -3.9126055863,50.0738199893,16764.0 -3.926404131,50.0694412212,16764.0 -3.9404365295,50.0653837191,16764.0 -3.9546847725,50.061652675,16764.0 -3.9691305873,50.058252862,16764.0 -3.9837554609,50.0551886287,16764.0 -3.9985406625,50.0524638934,16764.0 -4.0134672665,50.05008214,16764.0 -4.0285161756,50.0480464131,16764.0 -4.0436681441,50.0463593148,16764.0 -4.0589038012,50.0450230012,16764.0 -4.0742036748,50.04403918,16764.0 -4.0895482148,50.0434091085,16764.0 -4.104917817,50.0431335916,16764.0 -4.120292847,50.0432129814,16764.0 -4.1356536637,50.0436471765,16764.0 -4.1509806431,50.0444356221,16764.0 -4.1662542024,50.0455773107,16764.0 -4.1814548235,50.0470707833,16764.0 -4.1965630767,50.0489141315,16764.0 -4.2115596442,50.0511049992,16764.0 -4.2264253437,50.0536405859,16764.0 -4.241141152,50.05651765,16764.0 -4.2556882278,50.0597325127,16764.0 -4.2700479348,50.0632810627,16764.0 -4.2842018648,50.0671587608,16764.0 -4.2981318601,50.0713606457,16764.0 -4.311820036,50.0758813399,16764.0 -4.3252488027,50.0807150566,16764.0 -4.3384008876,50.0858556064,16764.0 -4.3512593561,50.0912964049,16764.0 -4.3638076335,50.097030481,16764.0 -4.3760295253,50.1030504853,16764.0 -4.387909238,50.109348699,16764.0 -4.3994313989,50.1159170439,16764.0 -4.4105810759,50.1227470915,16764.0 -4.4213437965,50.1298300744,16764.0 -4.4317055664,50.1371568961,16764.0 -4.4416528883,50.1447181433,16764.0 -4.4511727785,50.1525040966,16764.0 -4.4602527853,50.1605047435,16764.0 -4.4688810044,50.1687097899,16764.0 -4.4770460956,50.1771086739,16764.0 -4.484737298,50.1856905783,16764.0 -4.4919444444,50.1944444444,16764.0 + + + + + + EGD009A WEMBURY + <table border="1" cellpadding="1" cellspacing="0" row_id="1253" txt_name="WEMBURY"><tr><td>501904N 0040633W -<br/>501001N 0034740W -<br/>500623N 0035008W thence clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to<br/>501140N 0042931W -<br/>501904N 0040633W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC – Manageable.<br/><br/>Vertical Limit 22000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1091666667,50.3177777778,16764.0 -4.4919444444,50.1944444444,16764.0 -4.4849292755,50.1856225616,16764.0 -4.477234108,50.1770362709,16764.0 -4.4690648117,50.1686330948,16764.0 -4.460432153,50.160423856,16764.0 -4.4513474783,50.152419122,16764.0 -4.4418226976,50.1446291917,16764.0 -4.4318702695,50.1370640831,16764.0 -4.421503184,50.1297335201,16764.0 -4.4107349457,50.1226469211,16764.0 -4.3995795559,50.1158133869,16764.0 -4.3880514944,50.1092416896,16764.0 -4.376165701,50.1029402616,16764.0 -4.3639375563,50.0969171856,16764.0 -4.3513828619,50.0911801839,16764.0 -4.3385178203,50.0857366098,16764.0 -4.3253590148,50.0805934379,16764.0 -4.3119233883,50.0757572558,16764.0 -4.2982282225,50.071234256,16764.0 -4.2842911159,50.0670302284,16764.0 -4.2701299621,50.0631505531,16764.0 -4.2557629282,50.0596001938,16764.0 -4.2412084315,50.056383692,16764.0 -4.2264851176,50.0535051612,16764.0 -4.2116118373,50.0509682819,16764.0 -4.1966076236,50.0487762975,16764.0 -4.1814916682,50.0469320097,16764.0 -4.1662832985,50.0454377758,16764.0 -4.1510019541,50.0442955053,16764.0 -4.1356671629,50.0435066578,16764.0 -4.1202985175,50.0430722415,16764.0 -4.1049156516,50.0429928112,16764.0 -4.0895382162,50.0432684685,16764.0 -4.0741858556,50.0438988612,16764.0 -4.0588781838,50.0448831838,16764.0 -4.0436347606,50.0462201785,16764.0 -4.0284750679,50.0479081368,16764.0 -4.0134184863,50.0499449013,16764.0 -3.9984842711,50.0523278689,16764.0 -3.9836915291,50.0550539932,16764.0 -3.9690591956,50.0581197887,16764.0 -3.9546060106,50.0615213351,16764.0 -3.9403504966,50.0652542816,16764.0 -3.9263109353,50.0693138528,16764.0 -3.9125053453,50.0736948539,16764.0 -3.89895146,50.0783916776,16764.0 -3.8856667055,50.0833983106,16764.0 -3.8726681787,50.0887083411,16764.0 -3.8599726265,50.0943149665,16764.0 -3.8475964243,50.1002110019,16764.0 -3.8355555556,50.1063888889,16764.0 -3.7944444444,50.1669444444,16764.0 -4.1091666667,50.3177777778,16764.0 + + + + + + EGD009B WEMBURY + <table border="1" cellpadding="1" cellspacing="0" row_id="963" txt_name="WEMBURY"><tr><td>501342N 0042309W -<br/>501951N 0041015W thence clockwise by the arc of a circle radius 2.5 NM centred on 501904N 0040633W to<br/>501735N 0040325W -<br/>501904N 0040633W -<br/>501342N 0042309W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC – Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Plymouth Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.3858333333,50.2283333333,6705.6 -4.1091666667,50.3177777778,6705.6 -4.0569444444,50.2930555556,6705.6 -4.0536641121,50.2962012969,6705.6 -4.0508306672,50.2995200299,6705.6 -4.0484794125,50.3029899108,6705.6 -4.0466298918,50.3065822551,6705.6 -4.0452975128,50.3102673594,6705.6 -4.0444934154,50.3140147464,6705.6 -4.0442243764,50.3177934166,6705.6 -4.0444927492,50.3215721043,6705.6 -4.0452964397,50.3253195366,6705.6 -4.0466289201,50.3290046915,6705.6 -4.0484792784,50.3325970559,6705.6 -4.050832305,50.3360668781,6705.6 -4.0536686156,50.339385415,6705.6 -4.0569648077,50.3425251708,6705.6 -4.0606936531,50.3454601258,6705.6 -4.0648243209,50.3481659531,6705.6 -4.0693226319,50.3506202208,6705.6 -4.0741513417,50.3528025791,6705.6 -4.0792704488,50.3546949305,6705.6 -4.0846375278,50.3562815802,6705.6 -4.0902080822,50.3575493674,6705.6 -4.0959359153,50.3584877753,6705.6 -4.1017735161,50.3590890188,6705.6 -4.1076724557,50.3593481099,6705.6 -4.1135837926,50.3592628989,6705.6 -4.1194584815,50.3588340927,6705.6 -4.1252477834,50.3580652491,6705.6 -4.1309036735,50.3569627465,6705.6 -4.136379242,50.3555357309,6705.6 -4.1416290858,50.3537960396,6705.6 -4.1466096878,50.351758102,6705.6 -4.1512797789,50.3494388193,6705.6 -4.1556006814,50.3468574234,6705.6 -4.1595366302,50.3440353162,6705.6 -4.163055069,50.3409958917,6705.6 -4.1661269193,50.3377643405,6705.6 -4.1687268196,50.3343674403,6705.6 -4.1708333333,50.3308333333,6705.6 -4.3858333333,50.2283333333,6705.6 + + + + + + EGD011A OKEHAMPTON + <table border="1" cellpadding="1" cellspacing="0" row_id="964" txt_name="OKEHAMPTON"><tr><td>504226N 0040146W -<br/>504311N 0035854W -<br/>503937N 0035613W -<br/>503725N 0035712W -<br/>503744N 0035801W -<br/>503729N 0040101W -<br/>504019N 0040341W -<br/>504226N 0040146W <br/>Upper limit: 24100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC – Manageable above 10000 FT ALT.<br/><br/>Vertical Limits: Normally 10000 FT ALT. <br/><br/>Vertical Limits: OCNL notified to 24100 FT ALT. <br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.<br/><br/>Remarks: SI 1980/949. UAS BVLOS will not be conducted above 10000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0294444444,50.7072222222,7345.68 -4.0613888889,50.6719444444,7345.68 -4.0169444444,50.6247222222,7345.68 -3.9669444444,50.6288888889,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9369444444,50.6602777778,7345.68 -3.9816666667,50.7197222222,7345.68 -4.0294444444,50.7072222222,7345.68 + + + + + + EGD011B WILLSWORTHY + <table border="1" cellpadding="1" cellspacing="0" row_id="965" txt_name="WILLSWORTHY"><tr><td>504019N 0040341W -<br/>503729N 0040101W -<br/>503726N 0040136W -<br/>503550N 0040444W -<br/>503747N 0040558W -<br/>504019N 0040341W <br/>Upper limit: 24100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC – Manageable above 4500 FT ALT.<br/><br/>Vertical Limits: Normally 4500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to 24100 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.<br/><br/>Remarks: SI 1980/950. UAS BVLOS will not be conducted above 4500 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0613888889,50.6719444444,7345.68 -4.0994444444,50.6297222222,7345.68 -4.0788888889,50.5972222222,7345.68 -4.0266666667,50.6238888889,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0613888889,50.6719444444,7345.68 + + + + + + EGD011C MERRIVALE + <table border="1" cellpadding="1" cellspacing="0" row_id="966" txt_name="MERRIVALE"><tr><td>503726N 0040136W -<br/>503729N 0040101W -<br/>503744N 0035801W -<br/>503725N 0035712W -<br/>503426N 0035832W -<br/>503402N 0040336W -<br/>503550N 0040444W -<br/>503726N 0040136W <br/>Upper limit: 24100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC – Manageable above 10000 FT ALT.<br/><br/>Vertical Limits: Normally 10000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to 24100 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.<br/><br/>Remarks: SI 1979/1721. UAS BVLOS will not be conducted above 10000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0266666667,50.6238888889,7345.68 -4.0788888889,50.5972222222,7345.68 -4.06,50.5672222222,7345.68 -3.9755555556,50.5738888889,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9669444444,50.6288888889,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0266666667,50.6238888889,7345.68 + + + + + + EGD012 LYME BAY NORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1553" txt_name="LYME BAY NORTH"><tr><td>504220N 0024500W -<br/>503400N 0024500W following the line of latitude to -<br/>503400N 0030500W -<br/>503000N 0031730W -<br/>503650N 0031500W -<br/>504106N 0030544W - then along the coastline to -<br/>504220N 0024500W <br/>Upper limit: 18000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.75,50.7055555556,5486.400000000001 -2.7539289167,50.7069818889,5486.400000000001 -2.7687341389,50.7115620278,5486.400000000001 -2.7852465278,50.7163986111,5486.400000000001 -2.7919162222,50.717073,5486.400000000001 -2.7971543056,50.7168574444,5486.400000000001 -2.8015669444,50.7180863333,5486.400000000001 -2.8077796667,50.71687425,5486.400000000001 -2.8110547222,50.7178408333,5486.400000000001 -2.8169062778,50.7203182778,5486.400000000001 -2.8306950556,50.7229190278,5486.400000000001 -2.8383291111,50.7219649722,5486.400000000001 -2.8451533056,50.7232648056,5486.400000000001 -2.8632228333,50.7273595556,5486.400000000001 -2.8797339722,50.7303860278,5486.400000000001 -2.8967570833,50.732233,5486.400000000001 -2.9061245,50.7329700278,5486.400000000001 -2.9145946944,50.731285,5486.400000000001 -2.9238843611,50.7280638889,5486.400000000001 -2.9262131111,50.7239981389,5486.400000000001 -2.9284638056,50.7231707778,5486.400000000001 -2.9318530833,50.7226041111,5486.400000000001 -2.9340910833,50.7211471667,5486.400000000001 -2.9342041389,50.7197072222,5486.400000000001 -2.9360313333,50.7189730556,5486.400000000001 -2.9438005278,50.7178311389,5486.400000000001 -2.9500746944,50.7128335,5486.400000000001 -2.9523317222,50.7123653889,5486.400000000001 -2.9613887778,50.7119313056,5486.400000000001 -2.9628106111,50.7121893889,5486.400000000001 -2.96587475,50.7096457222,5486.400000000001 -2.9731907222,50.7072464444,5486.400000000001 -2.9783781111,50.7046847222,5486.400000000001 -2.9843237222,50.7045447222,5486.400000000001 -2.9877430833,50.7055051389,5486.400000000001 -2.9900088333,50.7054859167,5486.400000000001 -2.9936640833,50.7041956667,5486.400000000001 -2.9989896667,50.7015418889,5486.400000000001 -3.0043338611,50.6997871111,5486.400000000001 -3.0073015,50.6994916667,5486.400000000001 -3.0135101667,50.6984485278,5486.400000000001 -3.0194490278,50.6980369722,5486.400000000001 -3.0249826389,50.6985280833,5486.400000000001 -3.0275488889,50.6993149722,5486.400000000001 -3.0350669722,50.6998780278,5486.400000000001 -3.0450162778,50.7014981389,5486.400000000001 -3.0491265556,50.7016410833,5486.400000000001 -3.0536555833,50.7015103056,5486.400000000001 -3.0611743056,50.7020716944,5486.400000000001 -3.0658449167,50.7019391389,5486.400000000001 -3.07263125,50.7014271944,5486.400000000001 -3.0748946944,50.7013163889,5486.400000000001 -3.077708,50.7004809444,5486.400000000001 -3.0799693056,50.7002801389,5486.400000000001 -3.0816249444,50.6983760556,5486.400000000001 -3.0843944167,50.6956520833,5486.400000000001 -3.0882003056,50.6948971111,5486.400000000001 -3.0891350833,50.6924599722,5486.400000000001 -3.0890976111,50.6908413889,5486.400000000001 -3.0911355,50.68713475,5486.400000000001 -3.0919200833,50.68433925,5486.400000000001 -3.0950402778,50.6845798056,5486.400000000001 -3.0955555556,50.685,5486.400000000001 -3.25,50.6138888889,5486.400000000001 -3.2916666667,50.5,5486.400000000001 -3.0833333333,50.5666666667,5486.400000000001 -2.9722222222,50.5666666667,5486.400000000001 -2.8611111111,50.5666666667,5486.400000000001 -2.75,50.5666666667,5486.400000000001 -2.75,50.7055555556,5486.400000000001 + + + + + + EGD013 LYME BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1554" txt_name="LYME BAY"><tr><td>503400N 0024500W -<br/>500200N 0024500W -<br/>500200N 0025800W -<br/>500800N 0030430W -<br/>502500N 0031730W -<br/>503000N 0031730W -<br/>503400N 0030500W -<br/>503400N 0024500W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit 22000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.75,50.5666666667,16764.0 -3.0833333333,50.5666666667,16764.0 -3.2916666667,50.5,16764.0 -3.2916666667,50.4166666667,16764.0 -3.075,50.1333333333,16764.0 -2.9666666667,50.0333333333,16764.0 -2.75,50.0333333333,16764.0 -2.75,50.5666666667,16764.0 + + + + + + EGD014 PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="1254" txt_name="PORTLAND"><tr><td>503818N 0023424W -<br/>503736N 0023230W -<br/>503530N 0022948W -<br/>503400N 0023124W -<br/>503400N 0023000W -<br/>502931N 0023000W -<br/>503400N 0024500W -<br/>503400N 0024200W -<br/>503700N 0024130W -<br/>503818N 0023424W <br/>Upper limit: 15000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit 5000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 15000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5733333333,50.6383333333,4572.0 -2.6916666667,50.6166666667,4572.0 -2.7,50.5666666667,4572.0 -2.75,50.5666666667,4572.0 -2.5,50.4919444444,4572.0 -2.5,50.5666666667,4572.0 -2.5233333333,50.5666666667,4572.0 -2.4966666667,50.5916666667,4572.0 -2.5416666667,50.6266666667,4572.0 -2.5733333333,50.6383333333,4572.0 + + + + + + EGD015 BOVINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="971" txt_name="BOVINGTON"><tr><td>A circle, 500 M radius, centred at 504324N 0021424W <br/>Upper limit: 3600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01929-403765.<br/><br/>Remarks: SI 1936/118.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.24,50.7278279975,1097.28 -2.2419105304,50.7276613075,1097.28 -2.2436793273,50.7271736038,1097.28 -2.2451751801,50.726401066,1097.28 -2.24628714,50.7254010021,1097.28 -2.2469327516,50.724247594,1097.28 -2.2470641634,50.7230263925,1097.28 -2.2466716685,50.7218279703,1097.28 -2.2457844129,50.7207412039,1097.28 -2.2444682231,50.7198466836,1097.28 -2.2428207176,50.7192107394,1097.28 -2.240964066,50.7188805253,1097.28 -2.239035934,50.7188805253,1097.28 -2.2371792824,50.7192107394,1097.28 -2.2355317769,50.7198466836,1097.28 -2.2342155871,50.7207412039,1097.28 -2.2333283315,50.7218279703,1097.28 -2.2329358366,50.7230263925,1097.28 -2.2330672484,50.724247594,1097.28 -2.23371286,50.7254010021,1097.28 -2.2348248199,50.726401066,1097.28 -2.2363206727,50.7271736038,1097.28 -2.2380894696,50.7276613075,1097.28 -2.24,50.7278279975,1097.28 + + + + + + EGD017 PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="1255" txt_name="PORTLAND"><tr><td>503400N 0024500W -<br/>502931N 0023000W -<br/>500200N 0023000W -<br/>500200N 0024500W -<br/>503400N 0024500W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit 22000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.75,50.5666666667,16764.0 -2.75,50.0333333333,16764.0 -2.5,50.0333333333,16764.0 -2.5,50.4919444444,16764.0 -2.75,50.5666666667,16764.0 + + + + + + EGD021 PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="1268" txt_name="PORTLAND"><tr><td>503500N 0022000W -<br/>503500N 0021614W -<br/>503154N 0021624W -<br/>503000N 0021700W -<br/>502918N 0021718W -<br/>502500N 0021500W -<br/>502931N 0023000W -<br/>503000N 0023000W -<br/>503000N 0022000W -<br/>503500N 0022000W <br/>Upper limit: 15000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3333333333,50.5833333333,4572.0 -2.3333333333,50.5,4572.0 -2.5,50.5,4572.0 -2.5,50.4919444444,4572.0 -2.25,50.4166666667,4572.0 -2.2883333333,50.4883333333,4572.0 -2.2833333333,50.5,4572.0 -2.2733333333,50.5316666667,4572.0 -2.2705555556,50.5833333333,4572.0 -2.3333333333,50.5833333333,4572.0 + + + + + + EGD023 PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="1269" txt_name="PORTLAND"><tr><td>502931N 0023000W -<br/>502500N 0021500W -<br/>500200N 0021500W -<br/>500200N 0023000W -<br/>502931N 0023000W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit 22000 FT ALT.<br/><br/>Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5,50.4919444444,16764.0 -2.5,50.0333333333,16764.0 -2.25,50.0333333333,16764.0 -2.25,50.4166666667,16764.0 -2.5,50.4919444444,16764.0 + + + + + + EGD026 LULWORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1270" txt_name="LULWORTH"><tr><td>504020N 0020755W -<br/>503950N 0020732W -<br/>503751N 0020753W -<br/>503644N 0020813W -<br/>503503N 0020440W -<br/>503030N 0020043W -<br/>502654N 0020230W -<br/>502500N 0020842W -<br/>502500N 0021500W -<br/>502918N 0021718W -<br/>503000N 0021700W -<br/>503154N 0021624W -<br/>503536N 0021612W -<br/>503700N 0021447W -<br/>503800N 0021430W -<br/>503825N 0021137W -<br/>504028N 0021137W -<br/>504020N 0020755W <br/>Upper limit: 15000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: OCNL notified to ALT 20000.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS less than 150 KTS).<br/><br/>Service: SUACS not available during notified operating hours.<br/><br/>SUAAIS: Plymouth Military on 124.150 MHz when open, London Information on 124.750 MHz thereafter.<br/><br/>Contact: Booking: FOST Eastern Area Manager, Tel: 01752-557752 for the week before, FOST Duty Operations for the current week. Range Information on 01929-404859 or 01929-404712.<br/><br/>Remarks: SI 1978/1663. Unmanned Aircraft Systems (VLOS/BVLOS<br/>less than 150 KTS) will not be conducted above FL 115 and north of a line<br/>503813N 0021301W, 503746N 0021005W and 503810N 0020750W.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1319444444,50.6722222222,4572.0 -2.1936111111,50.6744444444,4572.0 -2.1936111111,50.6402777778,4572.0 -2.2416666667,50.6333333333,4572.0 -2.2463888889,50.6166666667,4572.0 -2.27,50.5933333333,4572.0 -2.2733333333,50.5316666667,4572.0 -2.2833333333,50.5,4572.0 -2.2883333333,50.4883333333,4572.0 -2.25,50.4166666667,4572.0 -2.145,50.4166666667,4572.0 -2.0416666667,50.4483333333,4572.0 -2.0119444444,50.5083333333,4572.0 -2.0777777778,50.5841666667,4572.0 -2.1369444444,50.6122222222,4572.0 -2.1313888889,50.6308333333,4572.0 -2.1255555556,50.6638888889,4572.0 -2.1319444444,50.6722222222,4572.0 + + + + + + EGD031 PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="1271" txt_name="PORTLAND"><tr><td>503626N 0015635W -<br/>503000N 0015635W -<br/>503000N 0020058W -<br/>503030N 0020043W -<br/>503412N 0020356W -<br/>503435N 0020320W - then along the coastline in an easterly direction to -<br/>503626N 0015635W <br/>Upper limit: 15000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9430555556,50.6072222222,4572.0 -1.9470027778,50.60445,4572.0 -1.9484166667,50.6030111111,4572.0 -1.9506833333,50.5973472222,4572.0 -1.9489916667,50.5944666667,4572.0 -1.9540805556,50.5921305556,4572.0 -1.9552111111,50.5911416667,4572.0 -1.9583222222,50.5903333333,4572.0 -1.9653861111,50.5907861111,4572.0 -1.9679277778,50.5904277778,4572.0 -1.9701888889,50.5907861111,4572.0 -1.9738611111,50.5901583333,4572.0 -1.9772527778,50.5899805556,4572.0 -1.9812083333,50.5894416667,4572.0 -1.9857305556,50.5900694444,4572.0 -1.9877083333,50.5896222222,4572.0 -1.9964666667,50.5903416667,4572.0 -2.0029666667,50.5899805556,4572.0 -2.0086194444,50.5895305556,4572.0 -2.014975,50.5888111111,4572.0 -2.0185083333,50.5880916667,4572.0 -2.0244416667,50.5871916667,4572.0 -2.0279722222,50.5851222222,4572.0 -2.0306527778,50.5829611111,4572.0 -2.0361611111,50.5798138889,4572.0 -2.0394083333,50.5784638889,4572.0 -2.0427972222,50.5772027778,4572.0 -2.0454805556,50.5765722222,4572.0 -2.049575,50.5761194444,4572.0 -2.0524,50.5754,4572.0 -2.0555555556,50.5763888889,4572.0 -2.0655555556,50.57,4572.0 -2.0119444444,50.5083333333,4572.0 -2.0161111111,50.5,4572.0 -1.9430555556,50.5,4572.0 -1.9430555556,50.6072222222,4572.0 + + + + + + EGD036 PORTSMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1272" txt_name="PORTSMOUTH"><tr><td>502927N 0011208W -<br/>500000N 0011126W -<br/>500000N 0014301W -<br/>500620N 0014207W -<br/>502927N 0011208W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit: 10000 FT ALT.<br/><br/>Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate or through Southampton or Jersey ATSUs, as appropriate.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2022222222,50.4908333333,16764.0 -1.7019444444,50.1055555556,16764.0 -1.7169444444,50.0,16764.0 -1.1905555556,50.0,16764.0 -1.2022222222,50.4908333333,16764.0 + + + + + + EGD037 PORTSMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1273" txt_name="PORTSMOUTH"><tr><td>503700N 0010211W -<br/>503700N 0003938W -<br/>503000N 0003213W -<br/>503000N 0011124W -<br/>503700N 0010211W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit: 10000 FT ALT.<br/><br/>Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0363888889,50.6166666667,16764.0 -1.19,50.5,16764.0 -0.5369444444,50.5,16764.0 -0.6605555556,50.6166666667,16764.0 -1.0363888889,50.6166666667,16764.0 + + + + + + EGD038 PORTSMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1274" txt_name="PORTSMOUTH"><tr><td>503000N 0011124W -<br/>503000N 0005000W -<br/>500000N 0005000W -<br/>500000N 0011126W -<br/>502927N 0011208W -<br/>503000N 0011124W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit: 10000 FT ALT.<br/><br/>Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.19,50.5,16764.0 -1.2022222222,50.4908333333,16764.0 -1.1905555556,50.0,16764.0 -0.8333333333,50.0,16764.0 -0.8333333333,50.5,16764.0 -1.19,50.5,16764.0 + + + + + + EGD039 PORTSMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1275" txt_name="PORTSMOUTH"><tr><td>503000N 0005000W -<br/>503000N 0003213W -<br/>502948N 0003200W -<br/>500000N 0003200W -<br/>500000N 0005000W -<br/>503000N 0005000W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit: 10000 FT ALT.<br/><br/>Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8333333333,50.5,16764.0 -0.8333333333,50.0,16764.0 -0.5333333333,50.0,16764.0 -0.5333333333,50.4966666667,16764.0 -0.5369444444,50.5,16764.0 -0.8333333333,50.5,16764.0 + + + + + + EGD040 PORTSMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1276" txt_name="PORTSMOUTH"><tr><td>502948N 0003200W -<br/>501347N 0001511W -<br/>500000N 0003155W -<br/>500000N 0003200W -<br/>502948N 0003200W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limit: 10000 FT ALT.<br/><br/>Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.<br/><br/>Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5333333333,50.4966666667,16764.0 -0.5333333333,50.0,16764.0 -0.5319444444,50.0,16764.0 -0.2530555556,50.2297222222,16764.0 -0.5333333333,50.4966666667,16764.0 + + + + + + EGD044 LYDD RANGES + <table border="1" cellpadding="1" cellspacing="0" row_id="1171" txt_name="LYDD RANGES"><tr><td>505525N 0005534E -<br/>505328N 0005613E -<br/>505238N 0005359E -<br/>505237N 0005015E -<br/>505420N 0004748E -<br/>505554N 0005009E -<br/>505650N 0005348E -<br/>505525N 0005534E <br/>Upper limit: 4000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225503.<br/><br/>Remarks: SI 1988/1465.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9261111111,50.9236111111,1219.2 0.8966666667,50.9472222222,1219.2 0.8358333333,50.9316666667,1219.2 0.7966666667,50.9055555556,1219.2 0.8375,50.8769444444,1219.2 0.8997222222,50.8772222222,1219.2 0.9369444444,50.8911111111,1219.2 0.9261111111,50.9236111111,1219.2 + + + + + + EGD061 WOODBURY COMMON + <table border="1" cellpadding="1" cellspacing="0" row_id="978" txt_name="WOODBURY COMMON"><tr><td>A circle, 926 M radius, centred at 504049N 0032051W <br/>Upper limit: 1500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Exeter APP on 128.980 MHz when open; at other times London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01395-272972.<br/><br/>Remarks: SI 2009/3284.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3475,50.6886019548,457.20000000000005 -3.3501377665,50.6884315287,457.20000000000005 -3.3526674871,50.6879272312,457.20000000000005 -3.3549855484,50.6871097185,457.20000000000005 -3.3569970187,50.6860124748,457.20000000000005 -3.3586195398,50.684680439,457.20000000000005 -3.3597866995,50.683168162,457.20000000000005 -3.3604507489,50.6815375708,457.20000000000005 -3.3605845512,50.6798554304,457.20000000000005 -3.3601826846,50.6781906099,457.20000000000005 -3.3592616556,50.6766112617,457.20000000000005 -3.3578592141,50.675182033,457.20000000000005 -3.356032801,50.6739614205,457.20000000000005 -3.3538571928,50.6729993786,457.20000000000005 -3.3514214394,50.6723352766,457.20000000000005 -3.348825222,50.67199629,457.20000000000005 -3.346174778,50.67199629,457.20000000000005 -3.3435785606,50.6723352766,457.20000000000005 -3.3411428072,50.6729993786,457.20000000000005 -3.338967199,50.6739614205,457.20000000000005 -3.3371407859,50.675182033,457.20000000000005 -3.3357383444,50.6766112617,457.20000000000005 -3.3348173154,50.6781906099,457.20000000000005 -3.3344154488,50.6798554304,457.20000000000005 -3.3345492511,50.6815375708,457.20000000000005 -3.3352133005,50.683168162,457.20000000000005 -3.3363804602,50.684680439,457.20000000000005 -3.3380029813,50.6860124748,457.20000000000005 -3.3400144516,50.6871097185,457.20000000000005 -3.3423325129,50.6879272312,457.20000000000005 -3.3448622335,50.6884315287,457.20000000000005 -3.3475,50.6886019548,457.20000000000005 + + + + + + EGD064A SOUTH WEST COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1555" txt_name="SOUTH WEST COMPLEX"><tr><td>512016N 0071115W -<br/>511616N 0061643W -<br/>502838N 0060046W -<br/>501752N 0070521W -<br/>502621N 0073603W -<br/>503808N 0074914W -<br/>504705N 0075207W -<br/>505745N 0075205W -<br/>512016N 0071115W <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -7.1874361111,51.3376777778,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8686888889,50.7846722222,20116.8 -7.820425,50.6354777778,20116.8 -7.6007361111,50.4391444444,20116.8 -7.0891277778,50.2977472222,20116.8 -6.0128138889,50.4771666667,20116.8 -6.2787027778,51.2711527778,20116.8 -7.1874361111,51.3376777778,20116.8 + + + + + relativeToGround + + + relativeToGround + -7.1874361111,51.3376777778,1524.0 -7.8681916667,50.9625111111,1524.0 -7.8686888889,50.7846722222,1524.0 -7.820425,50.6354777778,1524.0 -7.6007361111,50.4391444444,1524.0 -7.0891277778,50.2977472222,1524.0 -6.0128138889,50.4771666667,1524.0 -6.2787027778,51.2711527778,1524.0 -7.1874361111,51.3376777778,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.1874361111,51.3376777778,1524.0 -7.8681916667,50.9625111111,1524.0 -7.8681916667,50.9625111111,20116.8 -7.1874361111,51.3376777778,20116.8 -7.1874361111,51.3376777778,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.8681916667,50.9625111111,1524.0 -7.8686888889,50.7846722222,1524.0 -7.8686888889,50.7846722222,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8681916667,50.9625111111,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.8686888889,50.7846722222,1524.0 -7.820425,50.6354777778,1524.0 -7.820425,50.6354777778,20116.8 -7.8686888889,50.7846722222,20116.8 -7.8686888889,50.7846722222,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.820425,50.6354777778,1524.0 -7.6007361111,50.4391444444,1524.0 -7.6007361111,50.4391444444,20116.8 -7.820425,50.6354777778,20116.8 -7.820425,50.6354777778,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.6007361111,50.4391444444,1524.0 -7.0891277778,50.2977472222,1524.0 -7.0891277778,50.2977472222,20116.8 -7.6007361111,50.4391444444,20116.8 -7.6007361111,50.4391444444,1524.0 + + + + + relativeToGround + + + relativeToGround + -7.0891277778,50.2977472222,1524.0 -6.0128138889,50.4771666667,1524.0 -6.0128138889,50.4771666667,20116.8 -7.0891277778,50.2977472222,20116.8 -7.0891277778,50.2977472222,1524.0 + + + + + relativeToGround + + + relativeToGround + -6.0128138889,50.4771666667,1524.0 -6.2787027778,51.2711527778,1524.0 -6.2787027778,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524.0 + + + + + relativeToGround + + + relativeToGround + -6.2787027778,51.2711527778,1524.0 -7.1874361111,51.3376777778,1524.0 -7.1874361111,51.3376777778,20116.8 -6.2787027778,51.2711527778,20116.8 -6.2787027778,51.2711527778,1524.0 + + + + + + + EGD064B SOUTH WEST COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="979" txt_name="SOUTH WEST COMPLEX"><tr><td>511616N 0061643W -<br/>511207N 0052532W -<br/>510624N 0052510W -<br/>503012N 0054335W -<br/>502838N 0060046W -<br/>511616N 0061643W <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -6.2787027778,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.2020805556,20116.8 -6.2787027778,51.2711527778,20116.8 + + + + + relativeToGround + + + relativeToGround + -6.2787027778,51.2711527778,1524.0 -6.0128138889,50.4771666667,1524.0 -5.7262777778,50.5032416667,1524.0 -5.4195055556,51.1065583333,1524.0 -5.4255305556,51.2020805556,1524.0 -6.2787027778,51.2711527778,1524.0 + + + + + relativeToGround + + + relativeToGround + -6.2787027778,51.2711527778,1524.0 -6.0128138889,50.4771666667,1524.0 -6.0128138889,50.4771666667,20116.8 -6.2787027778,51.2711527778,20116.8 -6.2787027778,51.2711527778,1524.0 + + + + + relativeToGround + + + relativeToGround + -6.0128138889,50.4771666667,1524.0 -5.7262777778,50.5032416667,1524.0 -5.7262777778,50.5032416667,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.7262777778,50.5032416667,1524.0 -5.4195055556,51.1065583333,1524.0 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.4195055556,51.1065583333,1524.0 -5.4255305556,51.2020805556,1524.0 -5.4255305556,51.2020805556,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.4255305556,51.2020805556,1524.0 -6.2787027778,51.2711527778,1524.0 -6.2787027778,51.2711527778,20116.8 -5.4255305556,51.2020805556,20116.8 -5.4255305556,51.2020805556,1524.0 + + + + + + + EGD064C SOUTH WEST COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1556" txt_name="SOUTH WEST COMPLEX"><tr><td>511207N 0052532W -<br/>511028N 0050621W -<br/>505443N 0043352W -<br/>504712N 0043327W -<br/>504423N 0043914W -<br/>504328N 0043921W -<br/>503012N 0054335W -<br/>510624N 0052510W -<br/>511207N 0052532W <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -5.4255305556,51.2020805556,20116.8 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6538055556,50.7396694444,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5643666667,50.9120277778,20116.8 -5.1057833333,51.1745361111,20116.8 -5.4255305556,51.2020805556,20116.8 + + + + + relativeToGround + + + relativeToGround + -5.4255305556,51.2020805556,1524.0 -5.4195055556,51.1065583333,1524.0 -5.7262777778,50.5032416667,1524.0 -4.6557722222,50.7243333333,1524.0 -4.6538055556,50.7396694444,1524.0 -4.5574972222,50.7866166667,1524.0 -4.5643666667,50.9120277778,1524.0 -5.1057833333,51.1745361111,1524.0 -5.4255305556,51.2020805556,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.4255305556,51.2020805556,1524.0 -5.4195055556,51.1065583333,1524.0 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.2020805556,20116.8 -5.4255305556,51.2020805556,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.4195055556,51.1065583333,1524.0 -5.7262777778,50.5032416667,1524.0 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.7262777778,50.5032416667,1524.0 -4.6557722222,50.7243333333,1524.0 -4.6557722222,50.7243333333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524.0 + + + + + relativeToGround + + + relativeToGround + -4.6557722222,50.7243333333,1524.0 -4.6538055556,50.7396694444,1524.0 -4.6538055556,50.7396694444,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6557722222,50.7243333333,1524.0 + + + + + relativeToGround + + + relativeToGround + -4.6538055556,50.7396694444,1524.0 -4.5574972222,50.7866166667,1524.0 -4.5574972222,50.7866166667,20116.8 -4.6538055556,50.7396694444,20116.8 -4.6538055556,50.7396694444,1524.0 + + + + + relativeToGround + + + relativeToGround + -4.5574972222,50.7866166667,1524.0 -4.5643666667,50.9120277778,1524.0 -4.5643666667,50.9120277778,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5574972222,50.7866166667,1524.0 + + + + + relativeToGround + + + relativeToGround + -4.5643666667,50.9120277778,1524.0 -5.1057833333,51.1745361111,1524.0 -5.1057833333,51.1745361111,20116.8 -4.5643666667,50.9120277778,20116.8 -4.5643666667,50.9120277778,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.1057833333,51.1745361111,1524.0 -5.4255305556,51.2020805556,1524.0 -5.4255305556,51.2020805556,20116.8 -5.1057833333,51.1745361111,20116.8 -5.1057833333,51.1745361111,1524.0 + + + + + + + EGD110 BRAUNTON BURROWS + <table border="1" cellpadding="1" cellspacing="0" row_id="980" txt_name="BRAUNTON BURROWS"><tr><td>510602N 0041529W -<br/>510606N 0041203W -<br/>510500N 0041200W -<br/>510458N 0041315W -<br/>510516N 0041344W -<br/>510514N 0041527W -<br/>510602N 0041529W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 07870-377646 or 01395-277891.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.2580305556,51.1005694444,609.6 -4.2573722222,51.0870916667,609.6 -4.2288388889,51.0876416667,609.6 -4.2207555556,51.0828472222,609.6 -4.2000694444,51.0832388889,609.6 -4.2009444444,51.1016611111,609.6 -4.2580305556,51.1005694444,609.6 + + + + + + EGD113A CASTLEMARTIN + <table border="1" cellpadding="1" cellspacing="0" row_id="981" txt_name="CASTLEMARTIN"><tr><td>513937N 0051830W following the line of latitude to -<br/>513937N 0050443W -<br/>513906N 0050320W -<br/>513130N 0050530W -<br/>512900N 0050330W following the line of latitude to -<br/>512900N 0045432W -<br/>512430N 0050220W thence clockwise by the arc of a circle radius 18.1 NM centred on 514213N 0045647W to<br/>513610N 0052408W -<br/>513937N 0051830W <br/>Upper limit: 40000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: As detailed in activation NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.<br/><br/>Remarks: SI 1986/1834.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3083333333,51.6602777778,12192.0 -5.4022222222,51.6027777778,12192.0 -5.3963665818,51.5933780264,12192.0 -5.3901403276,51.5840734082,12192.0 -5.3834198158,51.5749035623,12192.0 -5.3762128249,51.5658786995,12192.0 -5.3685276609,51.5570088636,12192.0 -5.3603731468,51.5483039199,12192.0 -5.351758612,51.539773545,12192.0 -5.342693881,51.5314272159,12192.0 -5.3331892616,51.5232742004,12192.0 -5.3232555331,51.5153235465,12192.0 -5.3129039336,51.5075840732,12192.0 -5.3021461467,51.5000643609,12192.0 -5.2909942889,51.4927727422,12192.0 -5.2794608951,51.4857172931,12192.0 -5.2675589047,51.4789058244,12192.0 -5.2553016477,51.4723458735,12192.0 -5.2427028289,51.4660446964,12192.0 -5.2297765136,51.4600092598,12192.0 -5.216537112,51.454246234,12192.0 -5.2029993633,51.448761986,12192.0 -5.1891783197,51.4435625724,12192.0 -5.1750893305,51.4386537333,12192.0 -5.1607480254,51.4340408864,12192.0 -5.1461702976,51.4297291211,12192.0 -5.1313722874,51.4257231931,12192.0 -5.1163703645,51.4220275198,12192.0 -5.1011811112,51.4186461753,12192.0 -5.0858213045,51.4155828866,12192.0 -5.070307899,51.4128410291,12192.0 -5.0546580086,51.4104236237,12192.0 -5.0388888889,51.4083333333,12192.0 -4.9088888889,51.4833333333,12192.0 -4.9836111111,51.4833333333,12192.0 -5.0583333333,51.4833333333,12192.0 -5.0916666667,51.525,12192.0 -5.0555555556,51.6516666667,12192.0 -5.0786111111,51.6602777778,12192.0 -5.1934722222,51.6602777778,12192.0 -5.3083333333,51.6602777778,12192.0 + + + + + + EGD113B CASTLEMARTIN + <table border="1" cellpadding="1" cellspacing="0" row_id="982" txt_name="CASTLEMARTIN"><tr><td>513906N 0050320W thence clockwise by the arc of a circle radius 6.6 NM centred on 513230N 0050400W to<br/>513618N 0045520W -<br/>513618N 0045332W -<br/>513230N 0044830W -<br/>512900N 0045432W -<br/>512900N 0050330W -<br/>513130N 0050530W -<br/>513906N 0050320W <br/>Upper limit: 45000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: As detailed in activation NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.<br/><br/>Remarks: SI 1986/1834.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0555555556,51.6516666667,13716.0 -5.0916666667,51.525,13716.0 -5.0583333333,51.4833333333,13716.0 -4.9088888889,51.4833333333,13716.0 -4.8083333333,51.5416666667,13716.0 -4.8922222222,51.605,13716.0 -4.9222222222,51.605,13716.0 -4.9279167223,51.6100303992,13716.0 -4.9342578797,51.614754824,13716.0 -4.9410141992,51.6192510473,13716.0 -4.9481646133,51.62350497,13716.0 -4.9556867999,51.6275032486,13716.0 -4.9635572517,51.6312333384,13716.0 -4.9717513502,51.634683533,13716.0 -4.9802434429,51.6378430019,13716.0 -4.9890069249,51.6407018251,13716.0 -4.9980143228,51.6432510247,13716.0 -5.0072373821,51.6454825939,13716.0 -5.0166471575,51.6473895223,13716.0 -5.0262141049,51.6489658186,13716.0 -5.0359081761,51.6502065296,13716.0 -5.0456989152,51.6511077564,13716.0 -5.0555555556,51.6516666667,13716.0 + + + + + + EGD115A MANORBIER + <table border="1" cellpadding="1" cellspacing="0" row_id="983" txt_name="MANORBIER"><tr><td>513815N 0045012W thence clockwise by the arc of a circle radius 2 NM centred on 513815N 0044700W to<br/>513815N 0044348W -<br/>513815N 0045012W <br/>Upper limit: 27000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: As detailed in activation NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.<br/><br/>Remarks: SI 1941/158.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.8366666667,51.6375,8229.6 -4.73,51.6375,8229.6 -4.7302715604,51.6408567001,8229.6 -4.7310874734,51.6441790898,8229.6 -4.7324394857,51.6474330816,8229.6 -4.734313836,51.6505852827,8229.6 -4.7366913916,51.6536033378,8229.6 -4.7395478412,51.6564562626,8229.6 -4.7428539406,51.6591147623,8229.6 -4.746575811,51.6615515337,8229.6 -4.7506752849,51.6637415465,8229.6 -4.7551102976,51.6656623018,8229.6 -4.7598353191,51.6672940641,8229.6 -4.7648018228,51.6686200655,8229.6 -4.7699587861,51.6696266787,8229.6 -4.7752532169,51.6703035578,8229.6 -4.7806307011,51.6706437457,8229.6 -4.7860359656,51.6706437457,8229.6 -4.7914134498,51.6703035578,8229.6 -4.7967078805,51.6696266787,8229.6 -4.8018648438,51.6686200655,8229.6 -4.8068313476,51.6672940641,8229.6 -4.811556369,51.6656623018,8229.6 -4.8159913818,51.6637415465,8229.6 -4.8200908557,51.6615515337,8229.6 -4.8238127261,51.6591147623,8229.6 -4.8271188255,51.6564562626,8229.6 -4.829975275,51.6536033378,8229.6 -4.8323528307,51.6505852827,8229.6 -4.834227181,51.6474330816,8229.6 -4.8355791933,51.6441790898,8229.6 -4.8363951063,51.6408567001,8229.6 -4.8366666667,51.6375,8229.6 + + + + + + EGD115B MANORBIER + <table border="1" cellpadding="1" cellspacing="0" row_id="984" txt_name="MANORBIER"><tr><td>513815N 0045012W -<br/>513815N 0044348W -<br/>513345N 0043019W thence clockwise by the arc of a circle radius 11.34 NM centred on 513815N 0044700W to<br/>513208N 0050218W -<br/>513815N 0045012W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: As detailed in activation NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.<br/><br/>Remarks: SI 1941/158.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.8366666667,51.6375,15240.0 -5.0383333333,51.5355555556,15240.0 -5.0309417218,51.5288043613,15240.0 -5.0231463892,51.5222339864,15240.0 -5.0149045172,51.515879783,15240.0 -5.0062316321,51.509753581,15240.0 -4.9971440429,51.5038667816,15240.0 -4.9876588105,51.4982303358,15240.0 -4.9777937157,51.4928547252,15240.0 -4.9675672259,51.4877499426,15240.0 -4.9569984611,51.4829254744,15240.0 -4.946107158,51.478390283,15240.0 -4.934913634,51.4741527909,15240.0 -4.9234387502,51.4702208656,15240.0 -4.9117038729,51.4666018052,15240.0 -4.8997308346,51.4633023255,15240.0 -4.8875418953,51.460328548,15240.0 -4.8751597012,51.4576859887,15240.0 -4.8626072445,51.4553795484,15240.0 -4.849907822,51.4534135038,15240.0 -4.8370849928,51.4517915,15240.0 -4.8241625367,51.4505165438,15240.0 -4.8111644114,51.4495909985,15240.0 -4.7981147096,51.4490165796,15240.0 -4.785037616,51.4487943517,15240.0 -4.7719573642,51.4489247268,15240.0 -4.7588981934,51.449407463,15240.0 -4.7458843053,51.4502416659,15240.0 -4.7329398206,51.4514257891,15240.0 -4.7200887363,51.4529576379,15240.0 -4.7073548826,51.4548343726,15240.0 -4.6947618804,51.4570525138,15240.0 -4.6823330987,51.4596079487,15240.0 -4.6700916132,51.4624959382,15240.0 -4.6580601642,51.4657111258,15240.0 -4.646261116,51.4692475467,15240.0 -4.6347164165,51.4730986389,15240.0 -4.6234475573,51.4772572546,15240.0 -4.6124755347,51.4817156735,15240.0 -4.6018208114,51.4864656162,15240.0 -4.5915032789,51.4914982594,15240.0 -4.5815422215,51.4968042517,15240.0 -4.5719562797,51.5023737305,15240.0 -4.5627634166,51.5081963399,15240.0 -4.5539808837,51.514261249,15240.0 -4.5456251891,51.5205571722,15240.0 -4.5377120657,51.5270723892,15240.0 -4.5302564419,51.5337947665,15240.0 -4.5232724124,51.5407117792,15240.0 -4.5167732117,51.5478105344,15240.0 -4.5107711877,51.5550777941,15240.0 -4.5052777778,51.5625,15240.0 -4.73,51.6375,15240.0 -4.8366666667,51.6375,15240.0 + + + + + + EGD117 PENDINE + <table border="1" cellpadding="1" cellspacing="0" row_id="1644" txt_name="PENDINE"><tr><td>513510N 0042400W -<br/>513629N 0043752W -<br/>513958N 0043743W -<br/>514515N 0043300W -<br/>514524N 0042517W -<br/>514445N 0042400W -<br/>513510N 0042400W <br/>Upper limit: 27000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 23,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 27,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01994-452240.<br/><br/>Remarks: SI 1973/1627. UAS BVLOS will not be conducted above 10,000 FT ALT.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4,51.5861111111,8229.6 -4.4,51.7458333333,8229.6 -4.4213888889,51.7566666667,8229.6 -4.55,51.7541666667,8229.6 -4.6286111111,51.6661111111,8229.6 -4.6311111111,51.6080555556,8229.6 -4.4,51.5861111111,8229.6 + + + + + + EGD118 PEMBREY + <table border="1" cellpadding="1" cellspacing="0" row_id="1595" txt_name="PEMBREY"><tr><td>514625N 0042400W thence clockwise by the arc of a circle radius 3.5 NM centred on 514313N 0042144W to<br/>514001N 0042400W -<br/>514625N 0042400W <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 12,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS / SUAAIS: Pembrey Range on 122.750 MHz when open; at other times London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01554-892205.<br/><br/>Remarks: Associated aircraft operations outside area boundary; 122.750 MHz is a common frequency also used by Holbeach and Donna Nook AWRs. Ensure crossing clearance request is specific to Pembrey AWR. UAS BVLOS will not be conducted above 9000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4,51.7736111111,7010.400000000001 -4.4,51.6669444444,7010.400000000001 -4.3932089918,51.6652909723,7010.400000000001 -4.386237853,51.6639604701,7010.400000000001 -4.3791217654,51.6629707362,7010.400000000001 -4.3719036854,51.6623277443,7010.400000000001 -4.3646271782,51.6620353749,7010.400000000001 -4.3573361576,51.6620953927,7010.400000000001 -4.3500746236,51.6625074354,7010.400000000001 -4.3428864007,51.6632690162,7010.400000000001 -4.3358148759,51.6643755387,7010.400000000001 -4.3289027398,51.6658203243,7010.400000000001 -4.3221917315,51.6675946518,7010.400000000001 -4.3157223893,51.6696878099,7010.400000000001 -4.3095338075,51.6720871608,7010.400000000001 -4.3036634025,51.674778216,7010.400000000001 -4.2981466874,51.6777447228,7010.400000000001 -4.2930170582,51.6809687617,7010.400000000001 -4.2883055923,51.6844308533,7010.400000000001 -4.2840408602,51.6881100757,7010.400000000001 -4.2802487514,51.6919841894,7010.400000000001 -4.2769523168,51.6960297713,7010.400000000001 -4.2741716265,51.700222355,7010.400000000001 -4.2719236467,51.7045365786,7010.400000000001 -4.2702221333,51.7089463366,7010.400000000001 -4.2690775454,51.7134249384,7010.400000000001 -4.2684969787,51.7179452683,7010.400000000001 -4.268484118,51.7224799502,7010.400000000001 -4.2690392114,51.7270015129,7010.400000000001 -4.2701590641,51.7314825564,7010.400000000001 -4.2718370543,51.7358959184,7010.400000000001 -4.274063169,51.7402148389,7010.400000000001 -4.2768240608,51.7444131231,7010.400000000001 -4.2801031259,51.7484653009,7010.400000000001 -4.2838806013,51.7523467816,7010.400000000001 -4.2881336823,51.7560340046,7010.400000000001 -4.2928366585,51.7595045827,7010.400000000001 -4.2979610682,51.762737439,7010.400000000001 -4.3034758704,51.7657129363,7010.400000000001 -4.3093476325,51.7684129966,7010.400000000001 -4.3155407334,51.7708212126,7010.400000000001 -4.3220175804,51.7729229477,7010.400000000001 -4.328738839,51.7747054264,7010.400000000001 -4.3356636736,51.7761578122,7010.400000000001 -4.3427499972,51.7772712745,7010.400000000001 -4.3499547303,51.778039043,7010.400000000001 -4.3572340651,51.7784564488,7010.400000000001 -4.364543735,51.7785209536,7010.400000000001 -4.3718392867,51.7782321652,7010.400000000001 -4.3790763538,51.7775918398,7010.400000000001 -4.3862109299,51.7766038711,7010.400000000001 -4.3931996384,51.7752742668,7010.400000000001 -4.4,51.7736111111,7010.400000000001 + + + + + + EGD119 BRIDGWATER BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1173" txt_name="BRIDGWATER BAY"><tr><td>A circle, 4 NM radius, centred at 511224N 0031353W <br/>Upper limit: 5000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Yeovilton APP on 127.350 MHz when open; at other times London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information: RNAS Yeovilton Air Operations, Tel: 01935-455497. Booking: RNAS Yeovilton Air Weapons Supply, Tel: 01935-455449. Range Tower when manned, Tel: 01278-741337.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2313888889,51.2732537142,1524.0 -3.2391376971,51.2730758236,1524.0 -3.2468449835,51.2725431051,1524.0 -3.2544694515,51.2716584129,1524.0 -3.2619702543,51.2704264874,1524.0 -3.2693072156,51.2688539286,1524.0 -3.2764410482,51.266949161,1524.0 -3.2833335658,51.2647223876,1524.0 -3.2899478902,51.2621855343,1524.0 -3.2962486495,51.2593521862,1524.0 -3.3022021691,51.2562375131,1524.0 -3.3077766525,51.2528581878,1524.0 -3.3129423514,51.2492322963,1524.0 -3.3176717247,51.2453792395,1524.0 -3.321939585,51.241319629,1524.0 -3.3257232319,51.2370751757,1524.0 -3.3290025716,51.2326685731,1524.0 -3.3317602224,51.2281233748,1524.0 -3.3339816043,51.2234638686,1524.0 -3.3356550146,51.2187149454,1524.0 -3.336771687,51.2139019661,1524.0 -3.3373258345,51.209050626,1524.0 -3.337314677,51.2041868169,1524.0 -3.3367384523,51.1993364891,1524.0 -3.3356004111,51.1945255131,1524.0 -3.3339067956,51.1897795412,1524.0 -3.331666803,51.1851238715,1524.0 -3.3288925326,51.1805833133,1524.0 -3.3255989185,51.1761820552,1524.0 -3.3218036468,51.1719435371,1524.0 -3.3175270589,51.1678903259,1524.0 -3.3127920413,51.1640439963,1524.0 -3.3076239017,51.1604250162,1524.0 -3.3020502333,51.1570526395,1524.0 -3.2961007668,51.1539448039,1524.0 -3.2898072125,51.1511180366,1524.0 -3.2832030916,51.1485873672,1524.0 -3.2763235581,51.1463662487,1524.0 -3.2692052139,51.1444664867,1524.0 -3.2618859148,51.1428981776,1524.0 -3.254404572,51.1416696551,1524.0 -3.2468009466,51.1407874469,1524.0 -3.2391154415,51.1402562401,1524.0 -3.2313888889,51.1400788571,1524.0 -3.2236623363,51.1402562401,1524.0 -3.2159768312,51.1407874469,1524.0 -3.2083732058,51.1416696551,1524.0 -3.2008918629,51.1428981776,1524.0 -3.1935725639,51.1444664867,1524.0 -3.1864542197,51.1463662487,1524.0 -3.1795746862,51.1485873672,1524.0 -3.1729705652,51.1511180366,1524.0 -3.166677011,51.1539448039,1524.0 -3.1607275445,51.1570526395,1524.0 -3.155153876,51.1604250162,1524.0 -3.1499857365,51.1640439963,1524.0 -3.1452507189,51.1678903259,1524.0 -3.140974131,51.1719435371,1524.0 -3.1371788593,51.1761820552,1524.0 -3.1338852452,51.1805833133,1524.0 -3.1311109748,51.1851238715,1524.0 -3.1288709822,51.1897795412,1524.0 -3.1271773667,51.1945255131,1524.0 -3.1260393255,51.1993364891,1524.0 -3.1254631008,51.2041868169,1524.0 -3.1254519433,51.209050626,1524.0 -3.1260060908,51.2139019661,1524.0 -3.1271227631,51.2187149454,1524.0 -3.1287961735,51.2234638686,1524.0 -3.1310175554,51.2281233748,1524.0 -3.1337752061,51.2326685731,1524.0 -3.1370545459,51.2370751757,1524.0 -3.1408381928,51.241319629,1524.0 -3.145106053,51.2453792395,1524.0 -3.1498354263,51.2492322963,1524.0 -3.1550011252,51.2528581878,1524.0 -3.1605756087,51.2562375131,1524.0 -3.1665291283,51.2593521862,1524.0 -3.1728298876,51.2621855343,1524.0 -3.1794442119,51.2647223876,1524.0 -3.1863367296,51.266949161,1524.0 -3.1934705622,51.2688539286,1524.0 -3.2008075235,51.2704264874,1524.0 -3.2083083262,51.2716584129,1524.0 -3.2159327943,51.2725431051,1524.0 -3.2236400807,51.2730758236,1524.0 -3.2313888889,51.2732537142,1524.0 + + + + + + EGD120 BOSCOMBE DOWN + <table border="1" cellpadding="1" cellspacing="0" row_id="1596" txt_name="BOSCOMBE DOWN"><tr><td>511052N 0014802W -<br/>511059N 0014641W -<br/>511044N 0014308W -<br/>511105N 0014228W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>510844N 0014110W -<br/>510801N 0014248W -<br/>510730N 0014248W -<br/>510646N 0014409W -<br/>510746N 0014819W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to -<br/>511052N 0014802W <br/>Upper limit: 2500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS / SUAAIS: Boscombe Zone 126.700 MHz.<br/><br/>Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: This Danger Area is contained within the extant Boscombe Down ATZ; all regulations associated with flight within an ATZ remain applicable. Upper limit is expressed by reference to height, based on Boscombe Down QFE (identical to ATZ upper limit).<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8005555556,51.1811111111,762.0 -1.804205638,51.1781799843,762.0 -1.807520014,51.1751003506,762.0 -1.810383437,51.1718469736,762.0 -1.8127731156,51.1684458589,762.0 -1.8146700582,51.1649241872,762.0 -1.8160592224,51.1613100965,762.0 -1.8169296313,51.1576324567,762.0 -1.8172744577,51.1539206381,762.0 -1.817091075,51.1502042775,762.0 -1.8163810737,51.1465130403,762.0 -1.815150245,51.1428763847,762.0 -1.8134085306,51.1393233266,762.0 -1.8111699394,51.1358822079,762.0 -1.8084524327,51.1325804719,762.0 -1.8052777778,51.1294444444,762.0 -1.7358333333,51.1127777778,762.0 -1.7133333333,51.125,762.0 -1.7133333333,51.1336111111,762.0 -1.6861111111,51.1455555556,762.0 -1.6853632646,51.1491417891,762.0 -1.6850302822,51.1527499945,762.0 -1.6851969823,51.1563627495,762.0 -1.6858622209,51.1599527323,762.0 -1.6870210811,51.1634927871,762.0 -1.6886649068,51.1669561299,762.0 -1.6907813654,51.1703165508,762.0 -1.6933545375,51.1735486135,762.0 -1.6963650348,51.1766278481,762.0 -1.6997901449,51.1795309369,762.0 -1.7036040013,51.182235892,762.0 -1.7077777778,51.1847222222,762.0 -1.7188888889,51.1788888889,762.0 -1.7780555556,51.1830555556,762.0 -1.8005555556,51.1811111111,762.0 + + + + + + EGD122A WESSEX WEST + <table border="1" cellpadding="1" cellspacing="0" row_id="1597" txt_name="WESSEX WEST"><tr><td>511329N 0021149W -<br/>511106N 0020713W -<br/>511006N 0015702W -<br/>510125N 0015702W -<br/>505938N 0020714W -<br/>510120N 0021149W -<br/>511329N 0021149W <br/>Upper limit: FL160<br/>Lower limit: FL80<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.<br/><br/>Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122A and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.0222222222,4876.8 -2.1205555556,50.9938888889,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -2.1202777778,51.185,4876.8 -2.1969444444,51.2247222222,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.0222222222,2438.4 -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 + + + + + relativeToGround + + + relativeToGround + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.0222222222,2438.4 -2.1969444444,51.0222222222,4876.8 -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.2247222222,2438.4 + + + + + relativeToGround + + + relativeToGround + -2.1969444444,51.0222222222,2438.4 -2.1205555556,50.9938888889,2438.4 -2.1205555556,50.9938888889,4876.8 -2.1969444444,51.0222222222,4876.8 -2.1969444444,51.0222222222,2438.4 + + + + + relativeToGround + + + relativeToGround + -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -2.1205555556,50.9938888889,4876.8 -2.1205555556,50.9938888889,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1202777778,51.185,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + relativeToGround + + + relativeToGround + -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.2247222222,4876.8 -2.1202777778,51.185,4876.8 -2.1202777778,51.185,2438.4 + + + + + + + EGD122B WESSEX CENTRAL + <table border="1" cellpadding="1" cellspacing="0" row_id="985" txt_name="WESSEX CENTRAL"><tr><td>511059N 0014641W -<br/>511044N 0014308W -<br/>510357N 0014230W -<br/>510125N 0015702W -<br/>511006N 0015702W -<br/>511059N 0014641W <br/>Upper limit: FL160<br/>Lower limit: FL80<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.<br/><br/>Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122B and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -1.7780555556,51.1830555556,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7780555556,51.1830555556,4876.8 + + + + + relativeToGround + + + relativeToGround + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.7780555556,51.1830555556,4876.8 -1.7780555556,51.1830555556,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 -1.7780555556,51.1830555556,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + + + EGD122C WESSEX EAST + <table border="1" cellpadding="1" cellspacing="0" row_id="1598" txt_name="WESSEX EAST"><tr><td>511335N 0013725W -<br/>511236N 0013044W -<br/>510527N 0013342W -<br/>510357N 0014230W -<br/>511044N 0014308W -<br/>511233N 0013942W -<br/>511247N 0013759W -<br/>511335N 0013725W <br/>Upper limit: FL160<br/>Lower limit: FL80<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.<br/><br/>Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122C and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -1.6236111111,51.2263888889,4876.8 -1.6330555556,51.2130555556,4876.8 -1.6616666667,51.2091666667,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5122222222,51.21,4876.8 -1.6236111111,51.2263888889,4876.8 + + + + + relativeToGround + + + relativeToGround + -1.6236111111,51.2263888889,2438.4 -1.6330555556,51.2130555556,2438.4 -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21,2438.4 -1.6236111111,51.2263888889,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.6236111111,51.2263888889,2438.4 -1.6330555556,51.2130555556,2438.4 -1.6330555556,51.2130555556,4876.8 -1.6236111111,51.2263888889,4876.8 -1.6236111111,51.2263888889,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.6330555556,51.2130555556,2438.4 -1.6616666667,51.2091666667,2438.4 -1.6616666667,51.2091666667,4876.8 -1.6330555556,51.2130555556,4876.8 -1.6330555556,51.2130555556,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.6616666667,51.2091666667,4876.8 -1.6616666667,51.2091666667,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5616666667,51.0908333333,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21,2438.4 -1.5122222222,51.21,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5616666667,51.0908333333,2438.4 + + + + + relativeToGround + + + relativeToGround + -1.5122222222,51.21,2438.4 -1.6236111111,51.2263888889,2438.4 -1.6236111111,51.2263888889,4876.8 -1.5122222222,51.21,4876.8 -1.5122222222,51.21,2438.4 + + + + + + + EGD123 IMBER + <table border="1" cellpadding="1" cellspacing="0" row_id="1599" txt_name="IMBER"><tr><td>511724N 0020107W -<br/>511339N 0015746W -<br/>511348N 0015705W -<br/>511023N 0015325W -<br/>511006N 0015702W -<br/>511106N 0020713W -<br/>511329N 0021149W -<br/>511516N 0020939W -<br/>511705N 0020312W -<br/>511724N 0020107W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC Manageable.<br/><br/>Vertical Limit 3000 FT ALT H24.<br/><br/>Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).<br/><br/>Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730 when open.<br/><br/>Remarks: SI 1963/1293, SI 1981/1882.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0186111111,51.29,15240.0 -2.0533333333,51.2847222222,15240.0 -2.1608333333,51.2544444444,15240.0 -2.1969444444,51.2247222222,15240.0 -2.1202777778,51.185,15240.0 -1.9505555556,51.1683333333,15240.0 -1.8902777778,51.1730555556,15240.0 -1.9513888889,51.23,15240.0 -1.9627777778,51.2275,15240.0 -2.0186111111,51.29,15240.0 + + + + + + EGD124 LAVINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="986" txt_name="LAVINGTON"><tr><td>A circle, 1.5 NM radius, centred at 511527N 0015812W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710.<br/><br/>Remarks: SI 1981/1882.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.97,51.282470014,30449.52 -1.9747091708,51.2822946576,30449.52 -1.9793521288,51.2817710539,30449.52 -1.9838635968,51.2809065647,30449.52 -1.988180155,51.2797133442,30449.52 -1.992241136,51.2782081673,30449.52 -1.995989481,51.2764121923,30449.52 -1.9993725434,51.2743506631,30449.52 -2.0023428293,51.2720525523,30449.52 -2.0048586647,51.2695501529,30449.52 -2.0068847788,51.266878623,30449.52 -2.008392797,51.264075491,30449.52 -2.009361635,51.2611801269,30449.52 -2.0097777904,51.2582331885,30449.52 -2.0096355267,51.2552760504,30449.52 -2.0089369474,51.2523502221,30449.52 -2.0076919612,51.2494967662,30449.52 -2.005918137,51.246755722,30449.52 -2.0036404518,51.2441655445,30449.52 -2.0008909363,51.2417625661,30449.52 -1.9977082216,51.2395804878,30449.52 -1.9941369955,51.237649908,30449.52 -1.9902273742,51.235997895,30449.52 -1.9860342001,51.2346476088,30449.52 -1.9816162739,51.2336179772,30449.52 -1.9770355326,51.2329234326,30449.52 -1.972356185,51.2325737095,30449.52 -1.967643815,51.2325737095,30449.52 -1.9629644674,51.2329234326,30449.52 -1.9583837261,51.2336179772,30449.52 -1.9539657999,51.2346476088,30449.52 -1.9497726258,51.235997895,30449.52 -1.9458630045,51.237649908,30449.52 -1.9422917784,51.2395804878,30449.52 -1.9391090637,51.2417625661,30449.52 -1.9363595482,51.2441655445,30449.52 -1.934081863,51.246755722,30449.52 -1.9323080388,51.2494967662,30449.52 -1.9310630526,51.2523502221,30449.52 -1.9303644733,51.2552760504,30449.52 -1.9302222096,51.2582331885,30449.52 -1.930638365,51.2611801269,30449.52 -1.931607203,51.264075491,30449.52 -1.9331152212,51.266878623,30449.52 -1.9351413353,51.2695501529,30449.52 -1.9376571707,51.2720525523,30449.52 -1.9406274566,51.2743506631,30449.52 -1.944010519,51.2764121923,30449.52 -1.947758864,51.2782081673,30449.52 -1.951819845,51.2797133442,30449.52 -1.9561364032,51.2809065647,30449.52 -1.9606478712,51.2817710539,30449.52 -1.9652908292,51.2822946576,30449.52 -1.97,51.282470014,30449.52 + + + + + + EGD125 LARKHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="1600" txt_name="LARKHILL"><tr><td>511828N 0015004W -<br/>511059N 0014641W -<br/>511023N 0015325W -<br/>511348N 0015705W -<br/>511339N 0015746W -<br/>511724N 0020107W -<br/>511807N 0015635W -<br/>511828N 0015004W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC Manageable.<br/><br/>Vertical Limit 3000 FT ALT H24.<br/><br/>Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).<br/><br/>Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730.<br/><br/>Remarks: SI 1965/1327, SI 1981/1882.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8344444444,51.3077777778,15240.0 -1.9430555556,51.3019444444,15240.0 -2.0186111111,51.29,15240.0 -1.9627777778,51.2275,15240.0 -1.9513888889,51.23,15240.0 -1.8902777778,51.1730555556,15240.0 -1.7780555556,51.1830555556,15240.0 -1.8344444444,51.3077777778,15240.0 + + + + + + EGD126 BULFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="987" txt_name="BULFORD"><tr><td>511621N 0013746W -<br/>511525N 0013606W -<br/>511247N 0013759W -<br/>511233N 0013942W -<br/>511044N 0014308W -<br/>511059N 0014641W -<br/>511351N 0014759W thence clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to<br/>511354N 0014225W -<br/>511621N 0013746W <br/>Upper limit: FL90<br/>Lower limit: SFC <br/>Class: </td><td>AMC Manageable.<br/><br/>Vertical Limit 1400 FT ALT H24.<br/><br/>Vertical Limit OCNL notified up to FL 90 by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 01980-674730 or Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: SI 1970/1282, SI 1981/1882.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6294444444,51.2725,2743.2 -1.7069444444,51.2316666667,2743.2 -1.715059155,51.2334964065,2743.2 -1.7234325199,51.2348000136,2743.2 -1.7319235049,51.2357586607,2743.2 -1.7404960327,51.2363682739,2743.2 -1.7491136738,51.2366262626,2743.2 -1.757739804,51.2365315304,2743.2 -1.7663377624,51.2360844798,2743.2 -1.7748710099,51.2352870108,2743.2 -1.7833032865,51.2341425123,2743.2 -1.7915987684,51.2326558475,2743.2 -1.7997222222,51.2308333333,2743.2 -1.7780555556,51.1830555556,2743.2 -1.7188888889,51.1788888889,2743.2 -1.6616666667,51.2091666667,2743.2 -1.6330555556,51.2130555556,2743.2 -1.6016666667,51.2569444444,2743.2 -1.6294444444,51.2725,2743.2 + + + + + + EGD127 PORTON + <table border="1" cellpadding="1" cellspacing="0" row_id="988" txt_name="PORTON"><tr><td>510552N 0014315W -<br/>510632N 0014435W -<br/>510730N 0014248W -<br/>510801N 0014248W -<br/>511012N 0013750W -<br/>510752N 0013650W -<br/>510703N 0013843W -<br/>510552N 0014315W <br/>Upper limit: 12000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits:<br/>Upper Limit: ALT 12000 0600-1800 (0500-1700).<br/>Upper Limit: ALT 8000 (OCNL notified to ALT 12000) 1800-0600 (1700-0500).<br/><br/>Activity: Para Dropping / Ordnance, Munitions and Explosives / Electronic/optical hazards / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUACS / SUAAIS: Boscombe Down Zone on 126.700 MHz when open; at other times London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.<br/><br/>Remarks: SI 1977/1611.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7208333333,51.0977777778,3657.6000000000004 -1.6452777778,51.1175,3657.6000000000004 -1.6138888889,51.1311111111,3657.6000000000004 -1.6305555556,51.17,3657.6000000000004 -1.7133333333,51.1336111111,3657.6000000000004 -1.7133333333,51.125,3657.6000000000004 -1.7430555556,51.1088888889,3657.6000000000004 -1.7208333333,51.0977777778,3657.6000000000004 + + + + + + EGD128 EVERLEIGH + <table border="1" cellpadding="1" cellspacing="0" row_id="1643" txt_name="EVERLEIGH"><tr><td>511852N 0014215W -<br/>511621N 0013746W -<br/>511354N 0014225W thence anti-clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to<br/>511351N 0014759W -<br/>511828N 0015004W -<br/>511852N 0014215W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC Manageable<br/> <br/>Vertical Limit 1400 FT ALT H24<br/> <br/>Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information: Salisbury Operations, Tel: 01980-674710 or 674730.<br/><br/>Remarks: SI 1981/1882.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7041666667,51.3144444444,15240.0 -1.8344444444,51.3077777778,15240.0 -1.7997222222,51.2308333333,15240.0 -1.7915023174,51.2324672241,15240.0 -1.7832265947,51.2339503473,15240.0 -1.774814405,51.2350921193,15240.0 -1.7663014863,51.2358876884,15240.0 -1.7577240116,51.2363336739,15240.0 -1.7491184326,51.2364281804,15240.0 -1.7405213223,51.2361708064,15240.0 -1.7319692174,51.2355626455,15240.0 -1.7234984599,51.2346062823,15240.0 -1.7151450407,51.2333057807,15240.0 -1.7069444444,51.2316666667,15240.0 -1.6294444444,51.2725,15240.0 -1.7041666667,51.3144444444,15240.0 + + + + + + EGD129 WESTON-ON-THE-GREEN + <table border="1" cellpadding="1" cellspacing="0" row_id="1594" txt_name="WESTON-ON-THE-GREEN"><tr><td>A circle, 2 NM radius, centred at 515246N 0011320W <br/>Upper limit: FL120<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Para Dropping.<br/><br/>Service: SUAAIS: Brize Zone on 119.000 MHz. SUACS: Oxford Approach on 125.090 MHz.<br/><br/>Contact: Pre-flight information / Booking: Brize Norton, Tel: 01993-895147.<br/><br/>Remarks: Parachuting activity up to FL 135 may be conducted with London Control (Swanwick) permission. Regular activity SR-SS to FL 85 described in ENR 5.5.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2222222222,51.9127342248,3657.6 -1.2277568724,51.9125576553,3657.6 -1.2332327248,51.9120298224,3657.6 -1.2385916105,51.9111563334,3657.6 -1.2437766112,51.9099464672,3657.6 -1.2487326672,51.908413075,3657.6 -1.2534071653,51.9065724429,3657.6 -1.2577504999,51.9044441182,3657.6 -1.2617166009,51.9020507004,3657.6 -1.2652634235,51.8994176001,3657.6 -1.268353394,51.8965727679,3657.6 -1.270953807,51.8935463967,3657.6 -1.2730371699,51.8903705996,3657.6 -1.2745814917,51.8870790687,3657.6 -1.2755705115,51.8837067162,3657.6 -1.2759938668,51.8802893039,3657.6 -1.2758471977,51.8768630632,3657.6 -1.2751321884,51.8734643111,3657.6 -1.2738565432,51.870129065,3657.6 -1.2720338997,51.8668926615,3657.6 -1.2696836797,51.8637893825,3657.6 -1.2668308788,51.8608520931,3657.6 -1.2635057979,51.8581118942,3657.6 -1.2597437196,51.8555977944,3657.6 -1.2555845326,51.8533364043,3657.6 -1.2510723085,51.8513516557,3657.6 -1.2462548354,51.84966455,3657.6 -1.2411831132,51.8482929371,3657.6 -1.2359108155,51.8472513271,3657.6 -1.2304937247,51.8465507384,3657.6 -1.2249891449,51.8461985817,3657.6 -1.2194552996,51.8461985817,3657.6 -1.2139507197,51.8465507384,3657.6 -1.2085336289,51.8472513271,3657.6 -1.2032613312,51.8482929371,3657.6 -1.198189609,51.84966455,3657.6 -1.193372136,51.8513516557,3657.6 -1.1888599119,51.8533364043,3657.6 -1.1847007249,51.8555977944,3657.6 -1.1809386465,51.8581118942,3657.6 -1.1776135656,51.8608520931,3657.6 -1.1747607647,51.8637893825,3657.6 -1.1724105447,51.8668926615,3657.6 -1.1705879013,51.870129065,3657.6 -1.169312256,51.8734643111,3657.6 -1.1685972467,51.8768630632,3657.6 -1.1684505777,51.8802893039,3657.6 -1.1688739329,51.8837067162,3657.6 -1.1698629527,51.8870790687,3657.6 -1.1714072745,51.8903705996,3657.6 -1.1734906375,51.8935463967,3657.6 -1.1760910505,51.8965727679,3657.6 -1.179181021,51.8994176001,3657.6 -1.1827278436,51.9020507004,3657.6 -1.1866939445,51.9044441182,3657.6 -1.1910372791,51.9065724429,3657.6 -1.1957117772,51.908413075,3657.6 -1.2006678332,51.9099464672,3657.6 -1.2058528339,51.9111563334,3657.6 -1.2112117197,51.9120298224,3657.6 -1.2166875721,51.9125576553,3657.6 -1.2222222222,51.9127342248,3657.6 + + + + + + EGD130 LONGMOOR + <table border="1" cellpadding="1" cellspacing="0" row_id="1601" txt_name="LONGMOOR"><tr><td>510559N 0005213W -<br/>510541N 0004938W -<br/>510446N 0004940W -<br/>510426N 0005301W -<br/>510559N 0005213W <br/>Upper limit: 2300 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 1800 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 2300 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01420-483405.<br/><br/>Remarks: SI 1982/1179.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8702777778,51.0997222222,701.0400000000001 -0.8836111111,51.0738888889,701.0400000000001 -0.8277777778,51.0794444444,701.0400000000001 -0.8272222222,51.0947222222,701.0400000000001 -0.8702777778,51.0997222222,701.0400000000001 + + + + + + EGD132 ASH RANGES + <table border="1" cellpadding="1" cellspacing="0" row_id="989" txt_name="ASH RANGES"><tr><td>511745N 0003956W -<br/>511623N 0003942W -<br/>511548N 0004034W -<br/>511524N 0004300W -<br/>511606N 0004309W -<br/>511638N 0004259W -<br/>511732N 0004116W -<br/>511745N 0003956W <br/>Upper limit: 2500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.<br/><br/>Remarks: SI 1983/162.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6655555556,51.2958333333,762.0 -0.6877777778,51.2922222222,762.0 -0.7163888889,51.2772222222,762.0 -0.7191666667,51.2683333333,762.0 -0.7166666667,51.2566666667,762.0 -0.6761111111,51.2633333333,762.0 -0.6616666667,51.2730555556,762.0 -0.6655555556,51.2958333333,762.0 + + + + + + EGD133A PIRBRIGHT + <table border="1" cellpadding="1" cellspacing="0" row_id="1620" txt_name="PIRBRIGHT"><tr><td>511922N 0003907W -<br/>511915N 0003858W -<br/>511828N 0003951W -<br/>511816N 0004028W -<br/>511815N 0004103W -<br/>511830N 0004118W -<br/>511922N 0003907W <br/>Upper limit: 1200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6519444444,51.3227777778,365.76 -0.6883333333,51.3083333333,365.76 -0.6841666667,51.3041666667,365.76 -0.6744444444,51.3044444444,365.76 -0.6641666667,51.3077777778,365.76 -0.6494444444,51.3208333333,365.76 -0.6519444444,51.3227777778,365.76 + + + + + + EGD133B PIRBRIGHT + <table border="1" cellpadding="1" cellspacing="0" row_id="1619" txt_name="PIRBRIGHT"><tr><td>512040N 0004029W -<br/>512034N 0003957W -<br/>511922N 0003907W -<br/>511830N 0004118W -<br/>511915N 0004146W -<br/>512019N 0004158W -<br/>512040N 0004029W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 1200 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 2400 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6747222222,51.3444444444,731.52 -0.6994444444,51.3386111111,731.52 -0.6961111111,51.3208333333,731.52 -0.6883333333,51.3083333333,731.52 -0.6519444444,51.3227777778,731.52 -0.6658333333,51.3427777778,731.52 -0.6747222222,51.3444444444,731.52 + + + + + + EGD136 SHOEBURYNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="990" txt_name="SHOEBURYNESS"><tr><td>513217N 0004804E -<br/>513017N 0005104E -<br/>513030N 0004700E -<br/>513217N 0004804E <br/>Upper limit: 13000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.<br/><br/>Remarks: SI 1936/714.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.8011111111,51.5380555556,3962.4 0.7833333333,51.5083333333,3962.4 0.8511111111,51.5047222222,3962.4 0.8011111111,51.5380555556,3962.4 + + + + + + EGD138A SHOEBURYNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="992" txt_name="SHOEBURYNESS"><tr><td>514000N 0010400E -<br/>514000N 0011613E -<br/>513714N 0011203E -<br/>513714N 0005536E -<br/>514000N 0010400E <br/>Upper limit: 60000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 6000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.<br/><br/>Remarks: SI 1936/714.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0666666667,51.6666666667,18288.0 0.9266666667,51.6205555556,18288.0 1.2008333333,51.6205555556,18288.0 1.2702777778,51.6666666667,18288.0 1.0666666667,51.6666666667,18288.0 + + + + + + EGD138B SHOEBURYNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="993" txt_name="SHOEBURYNESS"><tr><td>514200N 0011124E -<br/>514200N 0011912E -<br/>514000N 0011613E -<br/>514000N 0010400E -<br/>514200N 0011124E <br/>Upper limit: 5000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.19,51.7,1524.0 1.0666666667,51.6666666667,1524.0 1.2702777778,51.6666666667,1524.0 1.32,51.7,1524.0 1.19,51.7,1524.0 + + + + + + EGD138C SHOEBURYNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="994" txt_name="SHOEBURYNESS"><tr><td>513700N 0005455E -<br/>513755N 0005740E -<br/>513638N 0005850E -<br/>513544N 0005620E -<br/>513700N 0005455E <br/>Upper limit: 6000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.<br/><br/>Remarks: May be activated at the same time as EGD138A and/or EGD138D as a separate activity.<br/><br/>Remarks: SI 1936/714.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9152777778,51.6166666667,1828.8000000000002 0.9388888889,51.5955555556,1828.8000000000002 0.9805555556,51.6105555556,1828.8000000000002 0.9611111111,51.6319444444,1828.8000000000002 0.9152777778,51.6166666667,1828.8000000000002 + + + + + + EGD138D SHOEBURYNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="991" txt_name="SHOEBURYNESS"><tr><td>513714N 0005536E -<br/>513714N 0011203E -<br/>513000N 0005300E -<br/>513009N 0005115E -<br/>513217N 0004804E -<br/>513400N 0005000E -<br/>513500N 0005018E -<br/>513541N 0005016E - then along the north coast of Foulness Island to<br/>513700N 0005455E -<br/>513714N 0005536E <br/>Upper limit: 60000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 13,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.<br/><br/>Remarks: SI 1936/714.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9266666667,51.6205555556,18288.0 0.9152777778,51.6166666667,18288.0 0.915875,51.61495,18288.0 0.913075,51.6141194444,18288.0 0.9085638889,51.6136,18288.0 0.9064277778,51.6141027778,18288.0 0.9046694444,51.6136972222,18288.0 0.9015722222,51.6126944444,18288.0 0.8996138889,51.6137333333,18288.0 0.8951472222,51.6139333333,18288.0 0.8891527778,51.6150694444,18288.0 0.877525,51.6140055556,18288.0 0.8742555556,51.6125583333,18288.0 0.87235,51.6098166667,18288.0 0.8720472222,51.6004694444,18288.0 0.87065,51.5966361111,18288.0 0.8677638889,51.5943666667,18288.0 0.8625527778,51.5918861111,18288.0 0.8590694444,51.5916111111,18288.0 0.8508555556,51.5919,18288.0 0.8451333333,51.5927583333,18288.0 0.8405138889,51.5927805556,18288.0 0.8377777778,51.5947222222,18288.0 0.8383333333,51.5833333333,18288.0 0.8333333333,51.5666666667,18288.0 0.8011111111,51.5380555556,18288.0 0.8541666667,51.5025,18288.0 0.8833333333,51.5,18288.0 1.2008333333,51.6205555556,18288.0 0.9266666667,51.6205555556,18288.0 + + + + + + EGD139 FINGRINGHOE + <table border="1" cellpadding="1" cellspacing="0" row_id="995" txt_name="FINGRINGHOE"><tr><td>515000N 0005458E -<br/>514954N 0005852E -<br/>514833N 0005848E -<br/>514839N 0005452E -<br/>515000N 0005458E <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 1500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 2000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01206-736149.<br/><br/>Remarks: SI 1974/665.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9161111111,51.8333333333,609.6 0.9144444444,51.8108333333,609.6 0.98,51.8091666667,609.6 0.9811111111,51.8316666667,609.6 0.9161111111,51.8333333333,609.6 + + + + + + EGD141 HYTHE RANGES + <table border="1" cellpadding="1" cellspacing="0" row_id="996" txt_name="HYTHE RANGES"><tr><td>510419N 0010426E -<br/>510212N 0010531E -<br/>510120N 0010148E -<br/>510158N 0010111E -<br/>510323N 0010214E -<br/>510419N 0010426E <br/>Upper limit: 3200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225879.<br/><br/>Remarks: SI 1966/814.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0738888889,51.0719444444,975.36 1.0372222222,51.0563888889,975.36 1.0197222222,51.0327777778,975.36 1.03,51.0222222222,975.36 1.0919444444,51.0366666667,975.36 1.0738888889,51.0719444444,975.36 + + + + + + EGD147 PONTRILAS + <table border="1" cellpadding="1" cellspacing="0" row_id="997" txt_name="PONTRILAS"><tr><td>A circle, 2 NM radius, centred at 515800N 0025300W <br/>Upper limit: 10000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Para Dropping / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: London Information 124.750 MHz.<br/><br/>Danger Area Authority: HQ Land.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8833333333,51.999955951,3048.0 -2.8888787335,51.9997793836,3048.0 -2.8943652213,51.9992515574,3048.0 -2.8997345145,51.9983780795,3048.0 -2.9049295838,51.9971682287,3048.0 -2.9098952622,51.9956348562,3048.0 -2.9145788343,51.9937942479,3048.0 -2.9189305979,51.9916659511,3048.0 -2.9229043934,51.9892725649,3048.0 -2.9264580946,51.9866395,3048.0 -2.9295540548,51.9837947065,3048.0 -2.9321595054,51.9807683771,3048.0 -2.9342469009,51.9775926246,3048.0 -2.9357942078,51.9743011406,3048.0 -2.9367851343,51.970928837,3048.0 -2.9372092981,51.967511475,3048.0 -2.9370623318,51.9640852856,3048.0 -2.9363459229,51.9606865852,3048.0 -2.9350677915,51.9573513906,3048.0 -2.933241602,51.9541150377,3048.0 -2.9308868144,51.9510118081,3048.0 -2.928028473,51.948074566,3048.0 -2.9246969379,51.9453344117,3048.0 -2.9209275601,51.9428203533,3048.0 -2.9167603059,51.9405590008,3048.0 -2.9122393324,51.9385742856,3048.0 -2.90741252,51.9368872085,3048.0 -2.9023309674,51.9355156188,3048.0 -2.8970484519,51.9344740267,3048.0 -2.8916208636,51.9337734501,3048.0 -2.8861056174,51.9334212994,3048.0 -2.8805610492,51.9334212994,3048.0 -2.8750458031,51.9337734501,3048.0 -2.8696182148,51.9344740267,3048.0 -2.8643356993,51.9355156188,3048.0 -2.8592541466,51.9368872085,3048.0 -2.8544273343,51.9385742856,3048.0 -2.8499063607,51.9405590008,3048.0 -2.8457391065,51.9428203533,3048.0 -2.8419697288,51.9453344117,3048.0 -2.8386381936,51.948074566,3048.0 -2.8357798523,51.9510118081,3048.0 -2.8334250647,51.9541150377,3048.0 -2.8315988752,51.9573513906,3048.0 -2.8303207437,51.9606865852,3048.0 -2.8296043349,51.9640852856,3048.0 -2.8294573685,51.967511475,3048.0 -2.8298815324,51.970928837,3048.0 -2.8308724589,51.9743011406,3048.0 -2.8324197658,51.9775926246,3048.0 -2.8345071613,51.9807683771,3048.0 -2.8371126119,51.9837947065,3048.0 -2.8402085721,51.9866395,3048.0 -2.8437622732,51.9892725649,3048.0 -2.8477360688,51.9916659511,3048.0 -2.8520878324,51.9937942479,3048.0 -2.8567714045,51.9956348562,3048.0 -2.8617370829,51.9971682287,3048.0 -2.8669321522,51.9983780795,3048.0 -2.8723014454,51.9992515574,3048.0 -2.8777879332,51.9997793836,3048.0 -2.8833333333,51.999955951,3048.0 + + + + + + EGD148 KEEVIL + <table border="1" cellpadding="1" cellspacing="0" row_id="12540" txt_name="KEEVIL"><tr><td>511744N 0021016W -<br/>511937N 0020745W -<br/>512055N 0020410W -<br/>511946N 0020305W -<br/>511705N 0020312W -<br/>511602N 0020657W -<br/>511701N 0020929W -<br/>511744N 0021016W <br/>Upper limit: 3200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS). <br/> <br/>Service: SUACS: Boscombe Down ATC on 126.700 MHz. SUAAIS: London Information on 124.750 MHz. <br/> <br/>Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710. <br/> <br/>Danger Area Authority: JHC HQ</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1710333333,51.2956888889,975.36 -2.1580805556,51.2835916667,975.36 -2.11575,51.2672444444,975.36 -2.0533333333,51.2847222222,975.36 -2.0513416667,51.3294194444,975.36 -2.0694666667,51.3487166667,975.36 -2.1292833333,51.3269444444,975.36 -2.1710333333,51.2956888889,975.36 + + + + + + EGD201A ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1763" txt_name="ABERPORTH"><tr><td>523427N 0052148W -<br/>520903N 0050057W -<br/>521000N 0050822W -<br/>521307N 0051616W -<br/>522013N 0052151W -<br/>523427N 0052148W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3634016667,52.5740336111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.2711694444,52.2185361111,30449.52 -5.13935,52.1667388889,30449.52 -5.0158333333,52.1508333333,30449.52 -5.3634016667,52.5740336111,30449.52 + + + + + + EGD201B ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1764" txt_name="ABERPORTH"><tr><td>530300N 0053000W -<br/>531500N 0053000W -<br/>532315N 0051017W -<br/>532255N 0050000W -<br/>531200N 0050000W -<br/>530715N 0045319W -<br/>530300N 0045319W following the line of latitude to -<br/>530300N 0053000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards. <br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.0108888889,53.05,30449.52 -4.8886111111,53.05,30449.52 -4.8886111111,53.1208333333,30449.52 -5.0,53.2,30449.52 -5.0,53.3819444444,30449.52 -5.1713888889,53.3875,30449.52 -5.5,53.25,30449.52 -5.5,53.05,30449.52 + + + + + + EGD201C ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1765" txt_name="ABERPORTH"><tr><td>525019N 0045319W -<br/>524500N 0044018W -<br/>524500N 0045319W -<br/>525019N 0045319W <br/>Upper limit: UNL<br/>Lower limit: FL145<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: SI 1976/64. <br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.8886111111,52.8387333333,30449.52 -4.8886111111,52.75,30449.52 -4.6716305556,52.75,30449.52 -4.8886111111,52.8387333333,30449.52 + + + + + relativeToGround + + + relativeToGround + -4.8886111111,52.8387333333,4419.6 -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.8886111111,52.8387333333,4419.6 + + + + + relativeToGround + + + relativeToGround + -4.8886111111,52.8387333333,4419.6 -4.8886111111,52.75,4419.6 -4.8886111111,52.75,30449.52 -4.8886111111,52.8387333333,30449.52 -4.8886111111,52.8387333333,4419.6 + + + + + relativeToGround + + + relativeToGround + -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.6716305556,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,52.75,4419.6 + + + + + relativeToGround + + + relativeToGround + -4.6716305556,52.75,4419.6 -4.8886111111,52.8387333333,4419.6 -4.8886111111,52.8387333333,30449.52 -4.6716305556,52.75,30449.52 -4.6716305556,52.75,4419.6 + + + + + + + EGD201D ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1766" txt_name="ABERPORTH"><tr><td>531035N 0053000W -<br/>530300N 0051612W following the line of latitude to -<br/>530300N 0053000W -<br/>531035N 0053000W <br/>Upper limit: UNL<br/>Lower limit: FL55<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: SI 1976/64.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -5.5,53.1764722222,30449.52 -5.5,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.2698722222,53.05,30449.52 -5.5,53.1764722222,30449.52 + + + + + relativeToGround + + + relativeToGround + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 + + + + + relativeToGround + + + relativeToGround + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.5,53.05,30449.52 -5.5,53.1764722222,30449.52 -5.5,53.1764722222,1676.4 + + + + + relativeToGround + + + relativeToGround + -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.3849361111,53.05,30449.52 -5.5,53.05,30449.52 -5.5,53.05,1676.4 + + + + + relativeToGround + + + relativeToGround + -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.2698722222,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.3849361111,53.05,1676.4 + + + + + relativeToGround + + + relativeToGround + -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 -5.5,53.1764722222,30449.52 -5.2698722222,53.05,30449.52 -5.2698722222,53.05,1676.4 + + + + + + + EGD201F ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1768" txt_name="ABERPORTH"><tr><td>521236N 0052244W -<br/>521000N 0050822W -<br/>520903N 0050057W -<br/>520840N 0043847W -<br/>520612N 0044900W -<br/>520816N 0051829W -<br/>521236N 0052244W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219. <br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3787709722,52.2100607222,30449.52 -5.3080555556,52.1377777778,30449.52 -4.8166666667,52.1033333333,30449.52 -4.646375,52.14435,30449.52 -5.0158333333,52.1508333333,30449.52 -5.13935,52.1667388889,30449.52 -5.3787709722,52.2100607222,30449.52 + + + + + + EGD201G ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1769" txt_name="ABERPORTH"><tr><td>524417N 0053000W -<br/>523427N 0052148W -<br/>522013N 0052151W -<br/>521307N 0051616W -<br/>521000N 0050822W -<br/>521236N 0052244W -<br/>522000N 0053000W -<br/>524417N 0053000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5,52.7380555556,30449.52 -5.5,52.3333333333,30449.52 -5.3787709722,52.2100607222,30449.52 -5.13935,52.1667388889,30449.52 -5.2711694444,52.2185361111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.3634016667,52.5740336111,30449.52 -5.5,52.7380555556,30449.52 + + + + + + EGD201H ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="2114" txt_name="ABERPORTH"><tr><td>523000N 0051806W following the line of latitude to -<br/>523000N 0041200W -<br/>521600N 0041200W -<br/>521000N 0042942W -<br/>520848N 0042904W -<br/>520702N 0043810W -<br/>520840N 0043847W -<br/>520903N 0050057W -<br/>523000N 0051806W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: SI 1976/64.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3016805556,52.5,30449.52 -5.0158333333,52.1508333333,30449.52 -4.646375,52.14435,30449.52 -4.6360805556,52.1171138889,30449.52 -4.4845083333,52.1468,30449.52 -4.495,52.1666666667,30449.52 -4.2,52.2666666667,30449.52 -4.2,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.8885503472,52.5,30449.52 -5.0262604167,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.3016805556,52.5,30449.52 + + + + + + EGD201J ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1762" txt_name="ABERPORTH"><tr><td>530300N 0053000W following the line of latitude to -<br/>530300N 0045319W -<br/>524500N 0045319W following the line of latitude to -<br/>524500N 0044018W -<br/>523316N 0041200W -<br/>523000N 0041200W following the line of latitude to -<br/>523000N 0051806W -<br/>524417N 0053000W -<br/>530300N 0053000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: SI 1976/64.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5,53.05,30449.52 -5.5,52.7380555556,30449.52 -5.3016805556,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.0262604167,52.5,30449.52 -4.8885503472,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.2,52.5,30449.52 -4.2,52.5544888889,30449.52 -4.6716666667,52.75,30449.52 -4.7801388889,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,53.05,30449.52 -5.0108888889,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.5,53.05,30449.52 + + + + + + EGD201K ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="10054" txt_name="ABERPORTH"><tr><td>522000N 0053000W -<br/>520816N 0051829W -<br/>521038N 0053000W -<br/>522000N 0053000W <br/>Upper limit: FL145<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5,52.3333333333,4419.6 -5.5,52.1772222222,4419.6 -5.3080555556,52.1377777778,4419.6 -5.5,52.3333333333,4419.6 + + + + + + EGD202A WEST WALES + <table border="1" cellpadding="1" cellspacing="0" row_id="1789" txt_name="WEST WALES"><tr><td>521250N 0042121W -<br/>521600N 0041200W -<br/>521545N 0040958W -<br/>520135N 0041430W -<br/>520019N 0042519W -<br/>521250N 0042121W <br/>Upper limit: FL100<br/>Lower limit: FL60<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/> <br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202A and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,3048.0 -4.4219444444,52.0052777778,3048.0 -4.2416666667,52.0263888889,3048.0 -4.1661111111,52.2625,3048.0 -4.2,52.2666666667,3048.0 -4.3558333333,52.2138888889,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,1828.8 -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.2,52.2666666667,1828.8 -4.3558333333,52.2138888889,1828.8 + + + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,1828.8 -4.4219444444,52.0052777778,1828.8 -4.4219444444,52.0052777778,3048.0 -4.3558333333,52.2138888889,3048.0 -4.3558333333,52.2138888889,1828.8 + + + + + relativeToGround + + + relativeToGround + -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.2416666667,52.0263888889,3048.0 -4.4219444444,52.0052777778,3048.0 -4.4219444444,52.0052777778,1828.8 + + + + + relativeToGround + + + relativeToGround + -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.1661111111,52.2625,3048.0 -4.2416666667,52.0263888889,3048.0 -4.2416666667,52.0263888889,1828.8 + + + + + relativeToGround + + + relativeToGround + -4.1661111111,52.2625,1828.8 -4.2,52.2666666667,1828.8 -4.2,52.2666666667,3048.0 -4.1661111111,52.2625,3048.0 -4.1661111111,52.2625,1828.8 + + + + + relativeToGround + + + relativeToGround + -4.2,52.2666666667,1828.8 -4.3558333333,52.2138888889,1828.8 -4.3558333333,52.2138888889,3048.0 -4.2,52.2666666667,3048.0 -4.2,52.2666666667,1828.8 + + + + + + + EGD202B WEST WALES + <table border="1" cellpadding="1" cellspacing="0" row_id="1790" txt_name="WEST WALES"><tr><td>521250N 0042121W -<br/>521600N 0041200W -<br/>521433N 0040004W -<br/>520320N 0040343W -<br/>520545N 0042336W -<br/>521250N 0042121W <br/>Upper limit: FL225<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz. <br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202B and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,6858.0 -4.3933333333,52.0958333333,6858.0 -4.0619444444,52.0555555556,6858.0 -4.0011111111,52.2425,6858.0 -4.2,52.2666666667,6858.0 -4.3558333333,52.2138888889,6858.0 + + + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,3048.0 -4.3933333333,52.0958333333,3048.0 -4.0619444444,52.0555555556,3048.0 -4.0011111111,52.2425,3048.0 -4.2,52.2666666667,3048.0 -4.3558333333,52.2138888889,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.3558333333,52.2138888889,3048.0 -4.3933333333,52.0958333333,3048.0 -4.3933333333,52.0958333333,6858.0 -4.3558333333,52.2138888889,6858.0 -4.3558333333,52.2138888889,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.3933333333,52.0958333333,3048.0 -4.0619444444,52.0555555556,3048.0 -4.0619444444,52.0555555556,6858.0 -4.3933333333,52.0958333333,6858.0 -4.3933333333,52.0958333333,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.0619444444,52.0555555556,3048.0 -4.0011111111,52.2425,3048.0 -4.0011111111,52.2425,6858.0 -4.0619444444,52.0555555556,6858.0 -4.0619444444,52.0555555556,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.0011111111,52.2425,3048.0 -4.2,52.2666666667,3048.0 -4.2,52.2666666667,6858.0 -4.0011111111,52.2425,6858.0 -4.0011111111,52.2425,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.2,52.2666666667,3048.0 -4.3558333333,52.2138888889,3048.0 -4.3558333333,52.2138888889,6858.0 -4.2,52.2666666667,6858.0 -4.2,52.2666666667,3048.0 + + + + + + + EGD202C WEST WALES + <table border="1" cellpadding="1" cellspacing="0" row_id="1791" txt_name="WEST WALES"><tr><td>521433N 0040004W -<br/>521047N 0033002W -<br/>520721N 0033015W -<br/>520501N 0033532W -<br/>520211N 0034019W -<br/>520030N 0034053W -<br/>520320N 0040343W -<br/>521433N 0040004W <br/>Upper limit: FL225<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219.<br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202C and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.0011111111,52.2425,6858.0 -4.0619444444,52.0555555556,6858.0 -3.6813888889,52.0083333333,6858.0 -3.6719444444,52.0363888889,6858.0 -3.5922222222,52.0836111111,6858.0 -3.5041666667,52.1225,6858.0 -3.5005555556,52.1797222222,6858.0 -4.0011111111,52.2425,6858.0 + + + + + relativeToGround + + + relativeToGround + -4.0011111111,52.2425,3048.0 -4.0619444444,52.0555555556,3048.0 -3.6813888889,52.0083333333,3048.0 -3.6719444444,52.0363888889,3048.0 -3.5922222222,52.0836111111,3048.0 -3.5041666667,52.1225,3048.0 -3.5005555556,52.1797222222,3048.0 -4.0011111111,52.2425,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.0011111111,52.2425,3048.0 -4.0619444444,52.0555555556,3048.0 -4.0619444444,52.0555555556,6858.0 -4.0011111111,52.2425,6858.0 -4.0011111111,52.2425,3048.0 + + + + + relativeToGround + + + relativeToGround + -4.0619444444,52.0555555556,3048.0 -3.6813888889,52.0083333333,3048.0 -3.6813888889,52.0083333333,6858.0 -4.0619444444,52.0555555556,6858.0 -4.0619444444,52.0555555556,3048.0 + + + + + relativeToGround + + + relativeToGround + -3.6813888889,52.0083333333,3048.0 -3.6719444444,52.0363888889,3048.0 -3.6719444444,52.0363888889,6858.0 -3.6813888889,52.0083333333,6858.0 -3.6813888889,52.0083333333,3048.0 + + + + + relativeToGround + + + relativeToGround + -3.6719444444,52.0363888889,3048.0 -3.5922222222,52.0836111111,3048.0 -3.5922222222,52.0836111111,6858.0 -3.6719444444,52.0363888889,6858.0 -3.6719444444,52.0363888889,3048.0 + + + + + relativeToGround + + + relativeToGround + -3.5922222222,52.0836111111,3048.0 -3.5041666667,52.1225,3048.0 -3.5041666667,52.1225,6858.0 -3.5922222222,52.0836111111,6858.0 -3.5922222222,52.0836111111,3048.0 + + + + + relativeToGround + + + relativeToGround + -3.5041666667,52.1225,3048.0 -3.5005555556,52.1797222222,3048.0 -3.5005555556,52.1797222222,6858.0 -3.5041666667,52.1225,6858.0 -3.5041666667,52.1225,3048.0 + + + + + relativeToGround + + + relativeToGround + -3.5005555556,52.1797222222,3048.0 -4.0011111111,52.2425,3048.0 -4.0011111111,52.2425,6858.0 -3.5005555556,52.1797222222,6858.0 -3.5005555556,52.1797222222,3048.0 + + + + + + + EGD202D WEST WALES + <table border="1" cellpadding="1" cellspacing="0" row_id="1770" txt_name="WEST WALES"><tr><td>520840N 0043847W -<br/>520702N 0043810W -<br/>520848N 0042904W -<br/>521000N 0042942W -<br/>521250N 0042121W -<br/>520019N 0042519W -<br/>515840N 0043902W -<br/>520555N 0044130W thence clockwise by the arc of a circle radius 5 NM centred on 520653N 0043334W to<br/>520801N 0044128W -<br/>520840N 0043847W <br/>Upper limit: FL125<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01239-813219. <br/><br/>Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202D and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.646375,52.14435,3810.0 -4.6911111111,52.1336111111,3810.0 -4.6923695661,52.1286290972,3810.0 -4.6934867815,52.1236458923,3810.0 -4.6941112708,52.118630173,3810.0 -4.6942409049,52.1136003736,3810.0 -4.6938753744,52.1085749736,3810.0 -4.6930161885,52.1035724304,3810.0 -4.6916666667,52.0986111111,3810.0 -4.6505555556,51.9777777778,3810.0 -4.4219444444,52.0052777778,3810.0 -4.3558333333,52.2138888889,3810.0 -4.495,52.1666666667,3810.0 -4.4845083333,52.1468,3810.0 -4.6360805556,52.1171138889,3810.0 -4.646375,52.14435,3810.0 + + + + + + EGD203 SENNYBRIDGE + <table border="1" cellpadding="1" cellspacing="0" row_id="1628" txt_name="SENNYBRIDGE"><tr><td>520743N 0032924W -<br/>520613N 0032645W -<br/>520451N 0032532W -<br/>520252N 0032804W -<br/>520156N 0032943W -<br/>520150N 0033139W -<br/>515858N 0033729W -<br/>515815N 0033935W -<br/>515947N 0034105W -<br/>520211N 0034019W -<br/>520501N 0033532W -<br/>520743N 0032924W <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits:<br/>Upper Limit: ALT 23000 Mon-Fri 0800-1800 (0700-1700).<br/>Upper Limit: ALT 18000 Mon-Fri 1800-0800 (1700-0700), Fri 1800 (1700) - Mon 0800 (0700).<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01874-635599.<br/><br/>Remarks: SI 1974/1773.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.49,52.1286111111,7010.400000000001 -3.5922222222,52.0836111111,7010.400000000001 -3.6719444444,52.0363888889,7010.400000000001 -3.6847222222,51.9963888889,7010.400000000001 -3.6597222222,51.9708333333,7010.400000000001 -3.6247222222,51.9827777778,7010.400000000001 -3.5275,52.0305555556,7010.400000000001 -3.4952777778,52.0322222222,7010.400000000001 -3.4677777778,52.0477777778,7010.400000000001 -3.4255555556,52.0808333333,7010.400000000001 -3.4458333333,52.1036111111,7010.400000000001 -3.49,52.1286111111,7010.400000000001 + + + + + + EGD206 CARDINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="1621" txt_name="CARDINGTON"><tr><td>A circle, 1 NM radius, centred at 520621N 0002521W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Balloons / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Cardington Met Office, Tel: 01234-744658, Mob: 07513-786573.<br/><br/>Danger Area Authority: MET Office.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4225,52.1224776037,1828.8000000000002 -0.4264370798,52.1223001664,1828.8000000000002 -0.4302901554,52.1217716404,1828.8000000000002 -0.433977021,52.1209033022,1828.8000000000002 -0.437419028,52.1197136782,1828.8000000000002 -0.4405427677,52.1182281473,1828.8000000000002 -0.4432816393,52.1164783985,1828.8000000000002 -0.4455772722,52.1145017531,1828.8000000000002 -0.4473807689,52.1123403669,1828.8000000000002 -0.4486537454,52.110040329,1828.8000000000002 -0.449369144,52.1076506782,1828.8000000000002 -0.4495118043,52.1052223559,1828.8000000000002 -0.4490787784,52.1028071196,1828.8000000000002 -0.4480793863,52.1004564396,1828.8000000000002 -0.4465350094,52.0982204027,1828.8000000000002 -0.4444786278,52.0961466457,1828.8000000000002 -0.4419541121,52.0942793417,1828.8000000000002 -0.4390152849,52.0926582613,1828.8000000000002 -0.4357247719,52.0913179268,1828.8000000000002 -0.4321526683,52.0902868787,1828.8000000000002 -0.4283750477,52.0895870705,1828.8000000000002 -0.4244723461,52.0892334015,1828.8000000000002 -0.4205276539,52.0892334015,1828.8000000000002 -0.4166249523,52.0895870705,1828.8000000000002 -0.4128473317,52.0902868787,1828.8000000000002 -0.4092752281,52.0913179268,1828.8000000000002 -0.4059847151,52.0926582613,1828.8000000000002 -0.4030458879,52.0942793417,1828.8000000000002 -0.4005213722,52.0961466457,1828.8000000000002 -0.3984649906,52.0982204027,1828.8000000000002 -0.3969206137,52.1004564396,1828.8000000000002 -0.3959212216,52.1028071196,1828.8000000000002 -0.3954881957,52.1052223559,1828.8000000000002 -0.395630856,52.1076506782,1828.8000000000002 -0.3963462546,52.110040329,1828.8000000000002 -0.3976192311,52.1123403669,1828.8000000000002 -0.3994227278,52.1145017531,1828.8000000000002 -0.4017183607,52.1164783985,1828.8000000000002 -0.4044572323,52.1182281473,1828.8000000000002 -0.407580972,52.1197136782,1828.8000000000002 -0.411022979,52.1209033022,1828.8000000000002 -0.4147098446,52.1217716404,1828.8000000000002 -0.4185629202,52.1223001664,1828.8000000000002 -0.4225,52.1224776037,1828.8000000000002 + + + + + + EGD207 HOLBEACH + <table border="1" cellpadding="1" cellspacing="0" row_id="1629" txt_name="HOLBEACH"><tr><td>524830N 0001200E -<br/>525400N 0000633E thence clockwise by the arc of a circle radius 6.5 NM centred on 525000N 0001500E to<br/>525300N 0002430E -<br/>524830N 0002000E -<br/>524830N 0001200E <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Holbeach Range on 122.750 MHz when open. SUAAIS: Holbeach Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Range Ops, Tel: 01406-550083. Booking: Range ATC, Tel: 01406-550364 Ext 7119.<br/><br/>Remarks: Airborne bookings and free-calling aircraft accepted subject to availability. Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Donna Nook and Pembrey AWRs. Ensure crossing clearance request is specific to Holbeach AWR. SI 1939/1608. UAS BVLOS will not be conducted above 18000 FT ALT (12000 FT ALT in the event of the activation of Contingency Airway T999).<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.2,52.8083333333,7010.400000000001 0.3333333333,52.8083333333,7010.400000000001 0.4083333333,52.8833333333,7010.400000000001 0.4035323371,52.888770376,7010.400000000001 0.3980704212,52.8939769833,7010.400000000001 0.3921256339,52.8989866717,7010.400000000001 0.3857172013,52.9037831019,7010.400000000001 0.3788658826,52.9083506248,7010.400000000001 0.3715939029,52.9126743334,7010.400000000001 0.3639248819,52.916740112,7010.400000000001 0.3558837567,52.9205346833,7010.400000000001 0.3474967008,52.9240456522,7010.400000000001 0.338791038,52.9272615471,7010.400000000001 0.3297951528,52.9301718581,7010.400000000001 0.3205383966,52.9327670721,7010.400000000001 0.3110509909,52.9350387042,7010.400000000001 0.3013639265,52.9369793263,7010.400000000001 0.2915088612,52.9385825917,7010.400000000001 0.2815180137,52.9398432563,7010.400000000001 0.2714240568,52.9407571964,7010.400000000001 0.2612600077,52.941321422,7010.400000000001 0.2510591185,52.9415340873,7010.400000000001 0.2408547639,52.9413944965,7010.400000000001 0.2306803307,52.9409031063,7010.400000000001 0.2205691054,52.9400615243,7010.400000000001 0.2105541631,52.9388725038,7010.400000000001 0.2006682571,52.9373399341,7010.400000000001 0.1909437092,52.9354688284,7010.400000000001 0.1814123023,52.933265306,7010.400000000001 0.1721051742,52.9307365725,7010.400000000001 0.1630527144,52.9278908959,7010.400000000001 0.1542844628,52.9247375784,7010.400000000001 0.1458290125,52.9212869258,7010.400000000001 0.1377139148,52.9175502132,7010.400000000001 0.1299655892,52.9135396473,7010.400000000001 0.1226092361,52.9092683259,7010.400000000001 0.1156687551,52.9047501946,7010.400000000001 0.1091666667,52.9,7010.400000000001 0.2,52.8083333333,7010.400000000001 + + + + + + EGD208 STANFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="998" txt_name="STANFORD"><tr><td>523315N 0004050E -<br/>523320N 0004500E -<br/>523255N 0004800E -<br/>523045N 0005000E -<br/>522650N 0005050E -<br/>522620N 0004830E -<br/>522800N 0004500E -<br/>522900N 0003900E -<br/>523100N 0004000E -<br/>523315N 0004050E <br/>Upper limit: 7500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 2500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 7500 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: Lakenheath Zone on 128.900 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01842-855367.<br/><br/>Remarks: SI 1970/909 & SI 1975/24 (Amendment).<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6805555556,52.5541666667,2286.0 0.6666666667,52.5166666667,2286.0 0.65,52.4833333333,2286.0 0.75,52.4666666667,2286.0 0.8083333333,52.4388888889,2286.0 0.8472222222,52.4472222222,2286.0 0.8333333333,52.5125,2286.0 0.8,52.5486111111,2286.0 0.75,52.5555555556,2286.0 0.6805555556,52.5541666667,2286.0 + + + + + + EGD211 SWYNNERTON + <table border="1" cellpadding="1" cellspacing="0" row_id="999" txt_name="SWYNNERTON"><tr><td>A circle, 0.5 NM radius, centred at 525352N 0021312W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.22,52.9060987986,731.52 -2.2227704214,52.9059284347,731.52 -2.2254273585,52.9054243214,731.52 -2.2278619831,52.9046071082,731.52 -2.2299745875,52.9035102684,731.52 -2.2316786715,52.9021787258,731.52 -2.2329044861,52.9006670125,731.52 -2.2336018855,52.8990370336,731.52 -2.2337423743,52.8973555298,731.52 -2.233320265,52.8956913442,731.52 -2.2323529,52.8941126028,731.52 -2.230879932,52.8926839271,731.52 -2.2289616929,52.8914637897,731.52 -2.2266767188,52.8905021241,731.52 -2.2241185345,52.8898382828,731.52 -2.221391828,52.8894994296,731.52 -2.218608172,52.8894994296,731.52 -2.2158814655,52.8898382828,731.52 -2.2133232812,52.8905021241,731.52 -2.2110383071,52.8914637897,731.52 -2.209120068,52.8926839271,731.52 -2.2076471,52.8941126028,731.52 -2.206679735,52.8956913442,731.52 -2.2062576257,52.8973555298,731.52 -2.2063981145,52.8990370336,731.52 -2.2070955139,52.9006670125,731.52 -2.2083213285,52.9021787258,731.52 -2.2100254125,52.9035102684,731.52 -2.2121380169,52.9046071082,731.52 -2.2145726415,52.9054243214,731.52 -2.2172295786,52.9059284347,731.52 -2.22,52.9060987986,731.52 + + + + + + EGD213 KINETON + <table border="1" cellpadding="1" cellspacing="0" row_id="1000" txt_name="KINETON"><tr><td>A circle, 700 M radius, centred at 520902N 0012656W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Coventry Information on 123.830 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01869-257489.<br/><br/>Danger Area Authority: HQ Land.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4488888889,52.1568465441,731.52 -1.4512476826,52.1566769462,731.52 -1.4534792617,52.1561772992,731.52 -1.4554632808,52.1553745497,731.52 -1.45709276,52.1543119889,731.52 -1.4582798567,52.1530469158,731.52 -1.4589606006,52.1516475448,731.52 -1.4590983369,52.1501893251,731.52 -1.4586856924,52.1487508716,731.52 -1.4577449627,52.1474097263,731.52 -1.4563268989,52.1462381789,731.52 -1.4545079643,52.1452993723,731.52 -1.4523862089,52.1446439021,731.52 -1.4500759857,52.1443070918,731.52 -1.4477017921,52.1443070918,731.52 -1.4453915689,52.1446439021,731.52 -1.4432698135,52.1452993723,731.52 -1.4414508789,52.1462381789,731.52 -1.4400328151,52.1474097263,731.52 -1.4390920853,52.1487508716,731.52 -1.4386794409,52.1501893251,731.52 -1.4388171771,52.1516475448,731.52 -1.4394979211,52.1530469158,731.52 -1.4406850178,52.1543119889,731.52 -1.4423144969,52.1553745497,731.52 -1.4442985161,52.1561772992,731.52 -1.4465300952,52.1566769462,731.52 -1.4488888889,52.1568465441,731.52 + + + + + + EGD215 NORTH LUFFENHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="1001" txt_name="NORTH LUFFENHAM"><tr><td>A circle, 610 M radius, centred at 523754N 0003557W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information: Guard Room, Tel: 01780-727644.<br/><br/>Danger Area Authority: HQ Land.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5991666667,52.6371483654,731.52 -0.6014074807,52.6369761266,731.52 -0.603507446,52.6364702366,731.52 -0.6053345765,52.635662493,731.52 -0.6067740508,52.6346036641,731.52 -0.6077354312,52.6333602954,731.52 -0.6081583435,52.6320105244,731.52 -0.6080162628,52.6306391677,731.52 -0.6073181676,52.6293323909,731.52 -0.6061079637,52.6281722944,731.52 -0.6044617146,52.6272317572,731.52 -0.6024828569,52.6265698611,731.52 -0.600295702,52.6262281824,731.52 -0.5980376314,52.6262281824,731.52 -0.5958504764,52.6265698611,731.52 -0.5938716188,52.6272317572,731.52 -0.5922253697,52.6281722944,731.52 -0.5910151658,52.6293323909,731.52 -0.5903170706,52.6306391677,731.52 -0.5901749898,52.6320105244,731.52 -0.5905979021,52.6333602954,731.52 -0.5915592825,52.6346036641,731.52 -0.5929987568,52.635662493,731.52 -0.5948258873,52.6364702366,731.52 -0.5969258527,52.6369761266,731.52 -0.5991666667,52.6371483654,731.52 + + + + + + EGD216 CREDENHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="1002" txt_name="CREDENHILL"><tr><td>A circle, 2 NM radius, centred at 520453N 0024806W <br/>Upper limit: 10000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 2300 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 10,000 FT ALT by NOTAM.<br/><br/>Activity: Para Dropping / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: London Information on 124.750 MHz.<br/><br/>Danger Area Authority: HQ Land.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8016666667,52.1146775213,3048.0 -2.8072262898,52.1145009569,3048.0 -2.8127268489,52.1139731394,3048.0 -2.8181099118,52.113099676,3048.0 -2.8233183024,52.1118898454,3048.0 -2.828296712,52.1103564987,3048.0 -2.8329922895,52.1085159218,3048.0 -2.8373552052,52.1063876615,3048.0 -2.8413391811,52.103994317,3048.0 -2.8449019829,52.1013612984,3048.0 -2.8480058678,52.0985165558,3048.0 -2.8506179835,52.0954902813,3048.0 -2.8527107142,52.0923145874,3048.0 -2.8542619706,52.089023165,3048.0 -2.8552554197,52.0856509256,3048.0 -2.8556806534,52.0822336298,3048.0 -2.8555332935,52.0788075078,3048.0 -2.854815033,52.0754088753,3048.0 -2.8535336121,52.0720737483,3048.0 -2.851702731,52.0688374621,3048.0 -2.8493419001,52.0657342973,3048.0 -2.8464762284,52.0627971173,3048.0 -2.8431361539,52.0600570218,3048.0 -2.8393571186,52.0575430179,3048.0 -2.835179191,52.0552817149,3048.0 -2.8306466414,52.0532970434,3048.0 -2.8258074726,52.0516100039,3048.0 -2.8207129137,52.0502384449,3048.0 -2.8154168795,52.0491968762,3048.0 -2.8099754026,52.0484963154,3048.0 -2.8044460442,52.0481441727,3048.0 -2.7988872891,52.0481441727,3048.0 -2.7933579308,52.0484963154,3048.0 -2.7879164539,52.0491968762,3048.0 -2.7826204196,52.0502384449,3048.0 -2.7775258607,52.0516100039,3048.0 -2.772686692,52.0532970434,3048.0 -2.7681541423,52.0552817149,3048.0 -2.7639762147,52.0575430179,3048.0 -2.7601971794,52.0600570218,3048.0 -2.7568571049,52.0627971173,3048.0 -2.7539914332,52.0657342973,3048.0 -2.7516306023,52.0688374621,3048.0 -2.7497997213,52.0720737483,3048.0 -2.7485183003,52.0754088753,3048.0 -2.7478000398,52.0788075078,3048.0 -2.74765268,52.0822336298,3048.0 -2.7480779137,52.0856509256,3048.0 -2.7490713628,52.089023165,3048.0 -2.7506226191,52.0923145874,3048.0 -2.7527153499,52.0954902813,3048.0 -2.7553274655,52.0985165558,3048.0 -2.7584313504,52.1013612984,3048.0 -2.7619941522,52.103994317,3048.0 -2.7659781281,52.1063876615,3048.0 -2.7703410438,52.1085159218,3048.0 -2.7750366213,52.1103564987,3048.0 -2.7800150309,52.1118898454,3048.0 -2.7852234215,52.113099676,3048.0 -2.7906064844,52.1139731394,3048.0 -2.7961070436,52.1145009569,3048.0 -2.8016666667,52.1146775213,3048.0 + + + + + + EGD217A LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8894" txt_name="LLANBEDR"><tr><td>525022N 0040522W -<br/>524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -<br/>525022N 0040522W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0894944444,52.8395527778,609.6 -4.0949801674,52.8415168258,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.8463462805,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.8360461149,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.8204666854,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.7939679192,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.7771277339,609.6 -4.1740439228,52.7743637754,609.6 -4.169200554,52.7718609805,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.763927912,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.7658040048,609.6 -4.0970911477,52.7673299578,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + + + EGD217B LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8914" txt_name="LLANBEDR"><tr><td>525306N 0040947W -<br/>525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>524617N 0040510W -<br/>524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -<br/>525306N 0040947W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1630888889,52.8850805556,609.6 -4.1716703219,52.8834892012,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.8706815036,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.8262726218,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.8156260152,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.7993690845,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.788608546,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.7542646557,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.732844725,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.7221473925,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.7257194444,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.7674051858,609.6 -4.1025466245,52.7658950291,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.7632904051,609.6 -4.1392747141,52.7637886869,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.7735167672,609.6 -4.1769825268,52.7761366151,609.6 -4.1810544573,52.7789918139,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.7996417197,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.8251433373,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + EGD217C LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8934" txt_name="LLANBEDR"><tr><td>524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>524617N 0040510W -<br/>524603N 0040510W -<br/>523933N 0041231W -<br/>524222N 0041917W -<br/>524942N 0041102W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.183775,52.8282916667,609.6 -4.3215111111,52.7062027778,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.7692187011,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.7658921562,609.6 -4.1084350162,52.7647013069,609.6 -4.1144906333,52.7638392941,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.763127287,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.8108761513,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.818201754,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.8250862609,609.6 -4.183775,52.8282916667,609.6 + + + + + + EGD217D LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8935" txt_name="LLANBEDR"><tr><td>524222N 0041917W -<br/>523933N 0041231W -<br/>523526N 0041712W -<br/>523816N 0042359W -<br/>524222N 0041917W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.3215111111,52.7062027778,1828.8000000000002 -4.3995916667,52.6376388889,1828.8000000000002 -4.2867416667,52.5906805556,1828.8000000000002 -4.2084722222,52.6592083333,1828.8000000000002 -4.3215111111,52.7062027778,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.3215111111,52.7062027778,609.6 -4.3995916667,52.6376388889,609.6 -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.3215111111,52.7062027778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.3215111111,52.7062027778,609.6 -4.3995916667,52.6376388889,609.6 -4.3995916667,52.6376388889,1828.8000000000002 -4.3215111111,52.7062027778,1828.8000000000002 -4.3215111111,52.7062027778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.3995916667,52.6376388889,609.6 -4.2867416667,52.5906805556,609.6 -4.2867416667,52.5906805556,1828.8000000000002 -4.3995916667,52.6376388889,1828.8000000000002 -4.3995916667,52.6376388889,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8000000000002 -4.2867416667,52.5906805556,1828.8000000000002 -4.2867416667,52.5906805556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2084722222,52.6592083333,609.6 -4.3215111111,52.7062027778,609.6 -4.3215111111,52.7062027778,1828.8000000000002 -4.2084722222,52.6592083333,1828.8000000000002 -4.2084722222,52.6592083333,609.6 + + + + + + + EGD217E LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8936" txt_name="LLANBEDR"><tr><td>525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to<br/>524333N 0040503W -<br/>525307N 0040530W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0916888889,52.8851638889,609.6 -4.08405,52.7257194444,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.7580811762,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.7827928341,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.7934954808,609.6 -3.9901348241,52.7989316381,609.6 -3.9897921305,52.8043931904,609.6 -3.9900416104,52.8098565941,609.6 -3.9908824103,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.8508464167,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + + + EGD217F LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8937" txt_name="LLANBEDR"><tr><td>525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to<br/>525307N 0040530W -<br/>525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>525028N 0040939W -<br/>525306N 0040947W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.8462864694,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.886398031,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.8879772819,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.8872395227,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + EGD217G LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8938" txt_name="LLANBEDR"><tr><td>525022N 0040522W -<br/>524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -<br/>525022N 0040522W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.0894944444,52.8395527778,1828.8000000000002 -4.0949801674,52.8415168258,1828.8000000000002 -4.1007438086,52.8431637779,1828.8000000000002 -4.1067350168,52.8444800679,1828.8000000000002 -4.1129021488,52.8454543458,1828.8000000000002 -4.1191920321,52.84607821,1828.8000000000002 -4.1255504268,52.8463462805,1828.8000000000002 -4.131922497,52.8462562454,1828.8000000000002 -4.1382532879,52.8458088811,1828.8000000000002 -4.1444882038,52.8450080457,1828.8000000000002 -4.1505734827,52.8438606453,1828.8000000000002 -4.1564566639,52.8423765741,1828.8000000000002 -4.1620870429,52.8405686282,1828.8000000000002 -4.1674161122,52.8384523943,1828.8000000000002 -4.1723979807,52.8360461149,1828.8000000000002 -4.1769897708,52.8333705291,1828.8000000000002 -4.1811519882,52.8304486936,1828.8000000000002 -4.184848862,52.8273057818,1828.8000000000002 -4.188048651,52.8239688666,1828.8000000000002 -4.1907239156,52.8204666854,1828.8000000000002 -4.1928517505,52.8168293921,1828.8000000000002 -4.1944139782,52.813088296,1828.8000000000002 -4.1953973017,52.8092755921,1828.8000000000002 -4.1957934135,52.8054240831,1828.8000000000002 -4.1955990621,52.8015668967,1828.8000000000002 -4.1948160749,52.7977372011,1828.8000000000002 -4.1934513366,52.7939679192,1828.8000000000002 -4.1915167256,52.7902914462,1828.8000000000002 -4.189029006,52.7867393717,1828.8000000000002 -4.1860096801,52.783342209,1828.8000000000002 -4.1824847989,52.7801291336,1828.8000000000002 -4.1784847357,52.7771277339,1828.8000000000002 -4.1740439228,52.7743637754,1828.8000000000002 -4.169200554,52.7718609805,1828.8000000000002 -4.1639962563,52.7696408264,1828.8000000000002 -4.1584757326,52.7677223618,1828.8000000000002 -4.1526863794,52.7661220445,1828.8000000000002 -4.1466778812,52.7648536015,1828.8000000000002 -4.1405017878,52.763927912,1828.8000000000002 -4.134211074,52.7633529149,1828.8000000000002 -4.1278596898,52.7631335411,1828.8000000000002 -4.1215021006,52.7632716721,1828.8000000000002 -4.115192825,52.7637661231,1828.8000000000002 -4.1089859706,52.764612654,1828.8000000000002 -4.1029347739,52.7658040048,1828.8000000000002 -4.0970911477,52.7673299578,1828.8000000000002 -4.0915052387,52.7691774242,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.0894944444,52.8395527778,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.8415168258,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.8463462805,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.8360461149,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.8204666854,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.7939679192,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.7771277339,609.6 -4.1740439228,52.7743637754,609.6 -4.169200554,52.7718609805,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.763927912,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.7658040048,609.6 -4.0970911477,52.7673299578,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.8415168258,609.6 -4.0949801674,52.8415168258,1828.8000000000002 -4.0894944444,52.8395527778,1828.8000000000002 -4.0894944444,52.8395527778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0949801674,52.8415168258,609.6 -4.1007438086,52.8431637779,609.6 -4.1007438086,52.8431637779,1828.8000000000002 -4.0949801674,52.8415168258,1828.8000000000002 -4.0949801674,52.8415168258,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1067350168,52.8444800679,1828.8000000000002 -4.1007438086,52.8431637779,1828.8000000000002 -4.1007438086,52.8431637779,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1129021488,52.8454543458,1828.8000000000002 -4.1067350168,52.8444800679,1828.8000000000002 -4.1067350168,52.8444800679,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1191920321,52.84607821,1828.8000000000002 -4.1129021488,52.8454543458,1828.8000000000002 -4.1129021488,52.8454543458,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1191920321,52.84607821,609.6 -4.1255504268,52.8463462805,609.6 -4.1255504268,52.8463462805,1828.8000000000002 -4.1191920321,52.84607821,1828.8000000000002 -4.1191920321,52.84607821,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1255504268,52.8463462805,609.6 -4.131922497,52.8462562454,609.6 -4.131922497,52.8462562454,1828.8000000000002 -4.1255504268,52.8463462805,1828.8000000000002 -4.1255504268,52.8463462805,609.6 + + + + + relativeToGround + + + relativeToGround + -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1382532879,52.8458088811,1828.8000000000002 -4.131922497,52.8462562454,1828.8000000000002 -4.131922497,52.8462562454,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1444882038,52.8450080457,1828.8000000000002 -4.1382532879,52.8458088811,1828.8000000000002 -4.1382532879,52.8458088811,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1505734827,52.8438606453,1828.8000000000002 -4.1444882038,52.8450080457,1828.8000000000002 -4.1444882038,52.8450080457,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1564566639,52.8423765741,1828.8000000000002 -4.1505734827,52.8438606453,1828.8000000000002 -4.1505734827,52.8438606453,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1620870429,52.8405686282,1828.8000000000002 -4.1564566639,52.8423765741,1828.8000000000002 -4.1564566639,52.8423765741,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1674161122,52.8384523943,1828.8000000000002 -4.1620870429,52.8405686282,1828.8000000000002 -4.1620870429,52.8405686282,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1674161122,52.8384523943,609.6 -4.1723979807,52.8360461149,609.6 -4.1723979807,52.8360461149,1828.8000000000002 -4.1674161122,52.8384523943,1828.8000000000002 -4.1674161122,52.8384523943,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1723979807,52.8360461149,609.6 -4.1769897708,52.8333705291,609.6 -4.1769897708,52.8333705291,1828.8000000000002 -4.1723979807,52.8360461149,1828.8000000000002 -4.1723979807,52.8360461149,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.1811519882,52.8304486936,1828.8000000000002 -4.1769897708,52.8333705291,1828.8000000000002 -4.1769897708,52.8333705291,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.184848862,52.8273057818,1828.8000000000002 -4.1811519882,52.8304486936,1828.8000000000002 -4.1811519882,52.8304486936,609.6 + + + + + relativeToGround + + + relativeToGround + -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.188048651,52.8239688666,1828.8000000000002 -4.184848862,52.8273057818,1828.8000000000002 -4.184848862,52.8273057818,609.6 + + + + + relativeToGround + + + relativeToGround + -4.188048651,52.8239688666,609.6 -4.1907239156,52.8204666854,609.6 -4.1907239156,52.8204666854,1828.8000000000002 -4.188048651,52.8239688666,1828.8000000000002 -4.188048651,52.8239688666,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1907239156,52.8204666854,609.6 -4.1928517505,52.8168293921,609.6 -4.1928517505,52.8168293921,1828.8000000000002 -4.1907239156,52.8204666854,1828.8000000000002 -4.1907239156,52.8204666854,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1944139782,52.813088296,1828.8000000000002 -4.1928517505,52.8168293921,1828.8000000000002 -4.1928517505,52.8168293921,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1953973017,52.8092755921,1828.8000000000002 -4.1944139782,52.813088296,1828.8000000000002 -4.1944139782,52.813088296,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1957934135,52.8054240831,1828.8000000000002 -4.1953973017,52.8092755921,1828.8000000000002 -4.1953973017,52.8092755921,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1955990621,52.8015668967,1828.8000000000002 -4.1957934135,52.8054240831,1828.8000000000002 -4.1957934135,52.8054240831,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1948160749,52.7977372011,1828.8000000000002 -4.1955990621,52.8015668967,1828.8000000000002 -4.1955990621,52.8015668967,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1948160749,52.7977372011,609.6 -4.1934513366,52.7939679192,609.6 -4.1934513366,52.7939679192,1828.8000000000002 -4.1948160749,52.7977372011,1828.8000000000002 -4.1948160749,52.7977372011,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1934513366,52.7939679192,609.6 -4.1915167256,52.7902914462,609.6 -4.1915167256,52.7902914462,1828.8000000000002 -4.1934513366,52.7939679192,1828.8000000000002 -4.1934513366,52.7939679192,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.189029006,52.7867393717,1828.8000000000002 -4.1915167256,52.7902914462,1828.8000000000002 -4.1915167256,52.7902914462,609.6 + + + + + relativeToGround + + + relativeToGround + -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1860096801,52.783342209,1828.8000000000002 -4.189029006,52.7867393717,1828.8000000000002 -4.189029006,52.7867393717,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1824847989,52.7801291336,1828.8000000000002 -4.1860096801,52.783342209,1828.8000000000002 -4.1860096801,52.783342209,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1824847989,52.7801291336,609.6 -4.1784847357,52.7771277339,609.6 -4.1784847357,52.7771277339,1828.8000000000002 -4.1824847989,52.7801291336,1828.8000000000002 -4.1824847989,52.7801291336,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1784847357,52.7771277339,609.6 -4.1740439228,52.7743637754,609.6 -4.1740439228,52.7743637754,1828.8000000000002 -4.1784847357,52.7771277339,1828.8000000000002 -4.1784847357,52.7771277339,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1740439228,52.7743637754,609.6 -4.169200554,52.7718609805,609.6 -4.169200554,52.7718609805,1828.8000000000002 -4.1740439228,52.7743637754,1828.8000000000002 -4.1740439228,52.7743637754,609.6 + + + + + relativeToGround + + + relativeToGround + -4.169200554,52.7718609805,609.6 -4.1639962563,52.7696408264,609.6 -4.1639962563,52.7696408264,1828.8000000000002 -4.169200554,52.7718609805,1828.8000000000002 -4.169200554,52.7718609805,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1584757326,52.7677223618,1828.8000000000002 -4.1639962563,52.7696408264,1828.8000000000002 -4.1639962563,52.7696408264,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1526863794,52.7661220445,1828.8000000000002 -4.1584757326,52.7677223618,1828.8000000000002 -4.1584757326,52.7677223618,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1466778812,52.7648536015,1828.8000000000002 -4.1526863794,52.7661220445,1828.8000000000002 -4.1526863794,52.7661220445,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1466778812,52.7648536015,609.6 -4.1405017878,52.763927912,609.6 -4.1405017878,52.763927912,1828.8000000000002 -4.1466778812,52.7648536015,1828.8000000000002 -4.1466778812,52.7648536015,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1405017878,52.763927912,609.6 -4.134211074,52.7633529149,609.6 -4.134211074,52.7633529149,1828.8000000000002 -4.1405017878,52.763927912,1828.8000000000002 -4.1405017878,52.763927912,609.6 + + + + + relativeToGround + + + relativeToGround + -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1278596898,52.7631335411,1828.8000000000002 -4.134211074,52.7633529149,1828.8000000000002 -4.134211074,52.7633529149,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.1215021006,52.7632716721,1828.8000000000002 -4.1278596898,52.7631335411,1828.8000000000002 -4.1278596898,52.7631335411,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.115192825,52.7637661231,1828.8000000000002 -4.1215021006,52.7632716721,1828.8000000000002 -4.1215021006,52.7632716721,609.6 + + + + + relativeToGround + + + relativeToGround + -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1089859706,52.764612654,1828.8000000000002 -4.115192825,52.7637661231,1828.8000000000002 -4.115192825,52.7637661231,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1089859706,52.764612654,609.6 -4.1029347739,52.7658040048,609.6 -4.1029347739,52.7658040048,1828.8000000000002 -4.1089859706,52.764612654,1828.8000000000002 -4.1089859706,52.764612654,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1029347739,52.7658040048,609.6 -4.0970911477,52.7673299578,609.6 -4.0970911477,52.7673299578,1828.8000000000002 -4.1029347739,52.7658040048,1828.8000000000002 -4.1029347739,52.7658040048,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0970911477,52.7673299578,609.6 -4.0915052387,52.7691774242,609.6 -4.0915052387,52.7691774242,1828.8000000000002 -4.0970911477,52.7673299578,1828.8000000000002 -4.0970911477,52.7673299578,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8000000000002 -4.0915052387,52.7691774242,1828.8000000000002 -4.0915052387,52.7691774242,609.6 + + + + + relativeToGround + + + relativeToGround + -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.086225,52.7713305556,609.6 + + + + + + + EGD217H LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8939" txt_name="LLANBEDR"><tr><td>525306N 0040947W -<br/>525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>524617N 0040510W -<br/>524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -<br/>525306N 0040947W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,1828.8000000000002 -4.1716703219,52.8834892012,1828.8000000000002 -4.1800610524,52.8815618217,1828.8000000000002 -4.1882253836,52.879307044,1828.8000000000002 -4.1961284314,52.8767345124,1828.8000000000002 -4.203736446,52.8738552286,1828.8000000000002 -4.2110169583,52.8706815036,1828.8000000000002 -4.2179389192,52.8672269048,1828.8000000000002 -4.2244728329,52.8635061966,1828.8000000000002 -4.2305908832,52.8595352771,1828.8000000000002 -4.2362670523,52.8553311089,1828.8000000000002 -4.2414772309,52.8509116461,1828.8000000000002 -4.24619932,52.8462957566,1828.8000000000002 -4.2504133239,52.8415031405,1828.8000000000002 -4.2541014336,52.836554246,1828.8000000000002 -4.2572481003,52.8314701808,1828.8000000000002 -4.2598400991,52.8262726218,1828.8000000000002 -4.2618665826,52.8209837219,1828.8000000000002 -4.2633191239,52.8156260152,1828.8000000000002 -4.2641917489,52.8102223209,1828.8000000000002 -4.2644809586,52.8047956454,1828.8000000000002 -4.2641857397,52.7993690845,1828.8000000000002 -4.263307566,52.7939657248,1828.8000000000002 -4.2618503879,52.788608546,1828.8000000000002 -4.2598206119,52.7833203228,1828.8000000000002 -4.2572270704,52.7781235288,1828.8000000000002 -4.2540809803,52.7730402409,1828.8000000000002 -4.2503958922,52.7680920465,1828.8000000000002 -4.2461876305,52.763299952,1828.8000000000002 -4.2414742231,52.7586842944,1828.8000000000002 -4.236275823,52.7542646557,1828.8000000000002 -4.2306146206,52.7500597804,1828.8000000000002 -4.2245147485,52.7460874972,1828.8000000000002 -4.2180021779,52.7423646436,1828.8000000000002 -4.2111046078,52.7389069959,1828.8000000000002 -4.2038513475,52.735729203,1828.8000000000002 -4.1962731925,52.732844725,1828.8000000000002 -4.1884022946,52.7302657772,1828.8000000000002 -4.180272027,52.7280032789,1828.8000000000002 -4.1719168439,52.7260668081,1828.8000000000002 -4.1633721365,52.7244645613,1828.8000000000002 -4.1546740851,52.7232033196,1828.8000000000002 -4.1458595084,52.7222884205,1828.8000000000002 -4.1369657097,52.7217237352,1828.8000000000002 -4.1280303217,52.7215116532,1828.8000000000002 -4.1190911504,52.7216530717,1828.8000000000002 -4.1101860173,52.7221473925,1828.8000000000002 -4.1013526024,52.7229925239,1828.8000000000002 -4.0926282873,52.7241848898,1828.8000000000002 -4.08405,52.7257194444,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.0913879573,52.7692223853,1828.8000000000002 -4.0968429653,52.7674051858,1828.8000000000002 -4.1025466245,52.7658950291,1828.8000000000002 -4.1084520974,52.7647043103,1828.8000000000002 -4.1145109035,52.763842802,1828.8000000000002 -4.1206733141,52.763317574,1828.8000000000002 -4.1268887576,52.7631329367,1828.8000000000002 -4.1331062308,52.7632904051,1828.8000000000002 -4.1392747141,52.7637886869,1828.8000000000002 -4.1453435863,52.7646236933,1828.8000000000002 -4.1512630371,52.7657885717,1828.8000000000002 -4.1569844719,52.7672737619,1828.8000000000002 -4.1624609086,52.7690670735,1828.8000000000002 -4.1676473604,52.7711537858,1828.8000000000002 -4.1725012037,52.7735167672,1828.8000000000002 -4.1769825268,52.7761366151,1828.8000000000002 -4.1810544573,52.7789918139,1828.8000000000002 -4.1846834655,52.7820589112,1828.8000000000002 -4.1878396407,52.7853127087,1828.8000000000002 -4.1904969392,52.7887264686,1828.8000000000002 -4.1926334009,52.7922721322,1828.8000000000002 -4.1942313326,52.7959205499,1828.8000000000002 -4.1952774577,52.7996417197,1828.8000000000002 -4.1957630298,52.803405034,1828.8000000000002 -4.1956839083,52.8071795305,1828.8000000000002 -4.1950405983,52.8109341468,1828.8000000000002 -4.1938382505,52.8146379764,1828.8000000000002 -4.1920866238,52.818260523,1828.8000000000002 -4.1898000094,52.8217719521,1828.8000000000002 -4.1869971173,52.8251433373,1828.8000000000002 -4.1837009258,52.8283468994,1828.8000000000002 -4.1799384954,52.8313562361,1828.8000000000002 -4.1757407482,52.8341465404,1828.8000000000002 -4.1711422147,52.8366948064,1828.8000000000002 -4.16618075,52.8389800201,1828.8000000000002 -4.1608972222,52.8409833333,1828.8000000000002 -4.1630888889,52.8850805556,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.8834892012,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.8706815036,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.8262726218,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.8156260152,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.7993690845,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.788608546,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.7542646557,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.732844725,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.7221473925,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.7257194444,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.7674051858,609.6 -4.1025466245,52.7658950291,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.7632904051,609.6 -4.1392747141,52.7637886869,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.7735167672,609.6 -4.1769825268,52.7761366151,609.6 -4.1810544573,52.7789918139,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.7996417197,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.8251433373,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.8834892012,609.6 -4.1716703219,52.8834892012,1828.8000000000002 -4.1630888889,52.8850805556,1828.8000000000002 -4.1630888889,52.8850805556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1716703219,52.8834892012,609.6 -4.1800610524,52.8815618217,609.6 -4.1800610524,52.8815618217,1828.8000000000002 -4.1716703219,52.8834892012,1828.8000000000002 -4.1716703219,52.8834892012,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1882253836,52.879307044,1828.8000000000002 -4.1800610524,52.8815618217,1828.8000000000002 -4.1800610524,52.8815618217,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.1961284314,52.8767345124,1828.8000000000002 -4.1882253836,52.879307044,1828.8000000000002 -4.1882253836,52.879307044,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.203736446,52.8738552286,1828.8000000000002 -4.1961284314,52.8767345124,1828.8000000000002 -4.1961284314,52.8767345124,609.6 + + + + + relativeToGround + + + relativeToGround + -4.203736446,52.8738552286,609.6 -4.2110169583,52.8706815036,609.6 -4.2110169583,52.8706815036,1828.8000000000002 -4.203736446,52.8738552286,1828.8000000000002 -4.203736446,52.8738552286,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2110169583,52.8706815036,609.6 -4.2179389192,52.8672269048,609.6 -4.2179389192,52.8672269048,1828.8000000000002 -4.2110169583,52.8706815036,1828.8000000000002 -4.2110169583,52.8706815036,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2244728329,52.8635061966,1828.8000000000002 -4.2179389192,52.8672269048,1828.8000000000002 -4.2179389192,52.8672269048,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2305908832,52.8595352771,1828.8000000000002 -4.2244728329,52.8635061966,1828.8000000000002 -4.2244728329,52.8635061966,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2362670523,52.8553311089,1828.8000000000002 -4.2305908832,52.8595352771,1828.8000000000002 -4.2305908832,52.8595352771,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.2414772309,52.8509116461,1828.8000000000002 -4.2362670523,52.8553311089,1828.8000000000002 -4.2362670523,52.8553311089,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.24619932,52.8462957566,1828.8000000000002 -4.2414772309,52.8509116461,1828.8000000000002 -4.2414772309,52.8509116461,609.6 + + + + + relativeToGround + + + relativeToGround + -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2504133239,52.8415031405,1828.8000000000002 -4.24619932,52.8462957566,1828.8000000000002 -4.24619932,52.8462957566,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2541014336,52.836554246,1828.8000000000002 -4.2504133239,52.8415031405,1828.8000000000002 -4.2504133239,52.8415031405,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2572481003,52.8314701808,1828.8000000000002 -4.2541014336,52.836554246,1828.8000000000002 -4.2541014336,52.836554246,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2572481003,52.8314701808,609.6 -4.2598400991,52.8262726218,609.6 -4.2598400991,52.8262726218,1828.8000000000002 -4.2572481003,52.8314701808,1828.8000000000002 -4.2572481003,52.8314701808,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2598400991,52.8262726218,609.6 -4.2618665826,52.8209837219,609.6 -4.2618665826,52.8209837219,1828.8000000000002 -4.2598400991,52.8262726218,1828.8000000000002 -4.2598400991,52.8262726218,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2618665826,52.8209837219,609.6 -4.2633191239,52.8156260152,609.6 -4.2633191239,52.8156260152,1828.8000000000002 -4.2618665826,52.8209837219,1828.8000000000002 -4.2618665826,52.8209837219,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2633191239,52.8156260152,609.6 -4.2641917489,52.8102223209,609.6 -4.2641917489,52.8102223209,1828.8000000000002 -4.2633191239,52.8156260152,1828.8000000000002 -4.2633191239,52.8156260152,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2644809586,52.8047956454,1828.8000000000002 -4.2641917489,52.8102223209,1828.8000000000002 -4.2641917489,52.8102223209,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2644809586,52.8047956454,609.6 -4.2641857397,52.7993690845,609.6 -4.2641857397,52.7993690845,1828.8000000000002 -4.2644809586,52.8047956454,1828.8000000000002 -4.2644809586,52.8047956454,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2641857397,52.7993690845,609.6 -4.263307566,52.7939657248,609.6 -4.263307566,52.7939657248,1828.8000000000002 -4.2641857397,52.7993690845,1828.8000000000002 -4.2641857397,52.7993690845,609.6 + + + + + relativeToGround + + + relativeToGround + -4.263307566,52.7939657248,609.6 -4.2618503879,52.788608546,609.6 -4.2618503879,52.788608546,1828.8000000000002 -4.263307566,52.7939657248,1828.8000000000002 -4.263307566,52.7939657248,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2618503879,52.788608546,609.6 -4.2598206119,52.7833203228,609.6 -4.2598206119,52.7833203228,1828.8000000000002 -4.2618503879,52.788608546,1828.8000000000002 -4.2618503879,52.788608546,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2572270704,52.7781235288,1828.8000000000002 -4.2598206119,52.7833203228,1828.8000000000002 -4.2598206119,52.7833203228,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2540809803,52.7730402409,1828.8000000000002 -4.2572270704,52.7781235288,1828.8000000000002 -4.2572270704,52.7781235288,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2503958922,52.7680920465,1828.8000000000002 -4.2540809803,52.7730402409,1828.8000000000002 -4.2540809803,52.7730402409,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2461876305,52.763299952,1828.8000000000002 -4.2503958922,52.7680920465,1828.8000000000002 -4.2503958922,52.7680920465,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.2414742231,52.7586842944,1828.8000000000002 -4.2461876305,52.763299952,1828.8000000000002 -4.2461876305,52.763299952,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2414742231,52.7586842944,609.6 -4.236275823,52.7542646557,609.6 -4.236275823,52.7542646557,1828.8000000000002 -4.2414742231,52.7586842944,1828.8000000000002 -4.2414742231,52.7586842944,609.6 + + + + + relativeToGround + + + relativeToGround + -4.236275823,52.7542646557,609.6 -4.2306146206,52.7500597804,609.6 -4.2306146206,52.7500597804,1828.8000000000002 -4.236275823,52.7542646557,1828.8000000000002 -4.236275823,52.7542646557,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2245147485,52.7460874972,1828.8000000000002 -4.2306146206,52.7500597804,1828.8000000000002 -4.2306146206,52.7500597804,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2180021779,52.7423646436,1828.8000000000002 -4.2245147485,52.7460874972,1828.8000000000002 -4.2245147485,52.7460874972,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2111046078,52.7389069959,1828.8000000000002 -4.2180021779,52.7423646436,1828.8000000000002 -4.2180021779,52.7423646436,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.2038513475,52.735729203,1828.8000000000002 -4.2111046078,52.7389069959,1828.8000000000002 -4.2111046078,52.7389069959,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2038513475,52.735729203,609.6 -4.1962731925,52.732844725,609.6 -4.1962731925,52.732844725,1828.8000000000002 -4.2038513475,52.735729203,1828.8000000000002 -4.2038513475,52.735729203,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1962731925,52.732844725,609.6 -4.1884022946,52.7302657772,609.6 -4.1884022946,52.7302657772,1828.8000000000002 -4.1962731925,52.732844725,1828.8000000000002 -4.1962731925,52.732844725,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.180272027,52.7280032789,1828.8000000000002 -4.1884022946,52.7302657772,1828.8000000000002 -4.1884022946,52.7302657772,609.6 + + + + + relativeToGround + + + relativeToGround + -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1719168439,52.7260668081,1828.8000000000002 -4.180272027,52.7280032789,1828.8000000000002 -4.180272027,52.7280032789,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1633721365,52.7244645613,1828.8000000000002 -4.1719168439,52.7260668081,1828.8000000000002 -4.1719168439,52.7260668081,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1546740851,52.7232033196,1828.8000000000002 -4.1633721365,52.7244645613,1828.8000000000002 -4.1633721365,52.7244645613,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1458595084,52.7222884205,1828.8000000000002 -4.1546740851,52.7232033196,1828.8000000000002 -4.1546740851,52.7232033196,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1369657097,52.7217237352,1828.8000000000002 -4.1458595084,52.7222884205,1828.8000000000002 -4.1458595084,52.7222884205,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1280303217,52.7215116532,1828.8000000000002 -4.1369657097,52.7217237352,1828.8000000000002 -4.1369657097,52.7217237352,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1190911504,52.7216530717,1828.8000000000002 -4.1280303217,52.7215116532,1828.8000000000002 -4.1280303217,52.7215116532,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1190911504,52.7216530717,609.6 -4.1101860173,52.7221473925,609.6 -4.1101860173,52.7221473925,1828.8000000000002 -4.1190911504,52.7216530717,1828.8000000000002 -4.1190911504,52.7216530717,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1101860173,52.7221473925,609.6 -4.1013526024,52.7229925239,609.6 -4.1013526024,52.7229925239,1828.8000000000002 -4.1101860173,52.7221473925,1828.8000000000002 -4.1101860173,52.7221473925,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.0926282873,52.7241848898,1828.8000000000002 -4.1013526024,52.7229925239,1828.8000000000002 -4.1013526024,52.7229925239,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0926282873,52.7241848898,609.6 -4.08405,52.7257194444,609.6 -4.08405,52.7257194444,1828.8000000000002 -4.0926282873,52.7241848898,1828.8000000000002 -4.0926282873,52.7241848898,609.6 + + + + + relativeToGround + + + relativeToGround + -4.08405,52.7257194444,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8000000000002 -4.08405,52.7257194444,1828.8000000000002 -4.08405,52.7257194444,609.6 + + + + + relativeToGround + + + relativeToGround + -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0913879573,52.7692223853,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.086225,52.7713305556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0913879573,52.7692223853,609.6 -4.0968429653,52.7674051858,609.6 -4.0968429653,52.7674051858,1828.8000000000002 -4.0913879573,52.7692223853,1828.8000000000002 -4.0913879573,52.7692223853,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0968429653,52.7674051858,609.6 -4.1025466245,52.7658950291,609.6 -4.1025466245,52.7658950291,1828.8000000000002 -4.0968429653,52.7674051858,1828.8000000000002 -4.0968429653,52.7674051858,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1025466245,52.7658950291,609.6 -4.1084520974,52.7647043103,609.6 -4.1084520974,52.7647043103,1828.8000000000002 -4.1025466245,52.7658950291,1828.8000000000002 -4.1025466245,52.7658950291,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1145109035,52.763842802,1828.8000000000002 -4.1084520974,52.7647043103,1828.8000000000002 -4.1084520974,52.7647043103,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1206733141,52.763317574,1828.8000000000002 -4.1145109035,52.763842802,1828.8000000000002 -4.1145109035,52.763842802,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1268887576,52.7631329367,1828.8000000000002 -4.1206733141,52.763317574,1828.8000000000002 -4.1206733141,52.763317574,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1268887576,52.7631329367,609.6 -4.1331062308,52.7632904051,609.6 -4.1331062308,52.7632904051,1828.8000000000002 -4.1268887576,52.7631329367,1828.8000000000002 -4.1268887576,52.7631329367,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1331062308,52.7632904051,609.6 -4.1392747141,52.7637886869,609.6 -4.1392747141,52.7637886869,1828.8000000000002 -4.1331062308,52.7632904051,1828.8000000000002 -4.1331062308,52.7632904051,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1392747141,52.7637886869,609.6 -4.1453435863,52.7646236933,609.6 -4.1453435863,52.7646236933,1828.8000000000002 -4.1392747141,52.7637886869,1828.8000000000002 -4.1392747141,52.7637886869,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1512630371,52.7657885717,1828.8000000000002 -4.1453435863,52.7646236933,1828.8000000000002 -4.1453435863,52.7646236933,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1569844719,52.7672737619,1828.8000000000002 -4.1512630371,52.7657885717,1828.8000000000002 -4.1512630371,52.7657885717,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1624609086,52.7690670735,1828.8000000000002 -4.1569844719,52.7672737619,1828.8000000000002 -4.1569844719,52.7672737619,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1676473604,52.7711537858,1828.8000000000002 -4.1624609086,52.7690670735,1828.8000000000002 -4.1624609086,52.7690670735,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1676473604,52.7711537858,609.6 -4.1725012037,52.7735167672,609.6 -4.1725012037,52.7735167672,1828.8000000000002 -4.1676473604,52.7711537858,1828.8000000000002 -4.1676473604,52.7711537858,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1725012037,52.7735167672,609.6 -4.1769825268,52.7761366151,609.6 -4.1769825268,52.7761366151,1828.8000000000002 -4.1725012037,52.7735167672,1828.8000000000002 -4.1725012037,52.7735167672,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1769825268,52.7761366151,609.6 -4.1810544573,52.7789918139,609.6 -4.1810544573,52.7789918139,1828.8000000000002 -4.1769825268,52.7761366151,1828.8000000000002 -4.1769825268,52.7761366151,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1810544573,52.7789918139,609.6 -4.1846834655,52.7820589112,609.6 -4.1846834655,52.7820589112,1828.8000000000002 -4.1810544573,52.7789918139,1828.8000000000002 -4.1810544573,52.7789918139,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1878396407,52.7853127087,1828.8000000000002 -4.1846834655,52.7820589112,1828.8000000000002 -4.1846834655,52.7820589112,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1904969392,52.7887264686,1828.8000000000002 -4.1878396407,52.7853127087,1828.8000000000002 -4.1878396407,52.7853127087,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1926334009,52.7922721322,1828.8000000000002 -4.1904969392,52.7887264686,1828.8000000000002 -4.1904969392,52.7887264686,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1942313326,52.7959205499,1828.8000000000002 -4.1926334009,52.7922721322,1828.8000000000002 -4.1926334009,52.7922721322,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1942313326,52.7959205499,609.6 -4.1952774577,52.7996417197,609.6 -4.1952774577,52.7996417197,1828.8000000000002 -4.1942313326,52.7959205499,1828.8000000000002 -4.1942313326,52.7959205499,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1952774577,52.7996417197,609.6 -4.1957630298,52.803405034,609.6 -4.1957630298,52.803405034,1828.8000000000002 -4.1952774577,52.7996417197,1828.8000000000002 -4.1952774577,52.7996417197,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1956839083,52.8071795305,1828.8000000000002 -4.1957630298,52.803405034,1828.8000000000002 -4.1957630298,52.803405034,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1950405983,52.8109341468,1828.8000000000002 -4.1956839083,52.8071795305,1828.8000000000002 -4.1956839083,52.8071795305,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1938382505,52.8146379764,1828.8000000000002 -4.1950405983,52.8109341468,1828.8000000000002 -4.1950405983,52.8109341468,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1920866238,52.818260523,1828.8000000000002 -4.1938382505,52.8146379764,1828.8000000000002 -4.1938382505,52.8146379764,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1898000094,52.8217719521,1828.8000000000002 -4.1920866238,52.818260523,1828.8000000000002 -4.1920866238,52.818260523,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1898000094,52.8217719521,609.6 -4.1869971173,52.8251433373,609.6 -4.1869971173,52.8251433373,1828.8000000000002 -4.1898000094,52.8217719521,1828.8000000000002 -4.1898000094,52.8217719521,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1869971173,52.8251433373,609.6 -4.1837009258,52.8283468994,609.6 -4.1837009258,52.8283468994,1828.8000000000002 -4.1869971173,52.8251433373,1828.8000000000002 -4.1869971173,52.8251433373,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1799384954,52.8313562361,1828.8000000000002 -4.1837009258,52.8283468994,1828.8000000000002 -4.1837009258,52.8283468994,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1757407482,52.8341465404,1828.8000000000002 -4.1799384954,52.8313562361,1828.8000000000002 -4.1799384954,52.8313562361,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.1711422147,52.8366948064,1828.8000000000002 -4.1757407482,52.8341465404,1828.8000000000002 -4.1757407482,52.8341465404,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.16618075,52.8389800201,1828.8000000000002 -4.1711422147,52.8366948064,1828.8000000000002 -4.1711422147,52.8366948064,609.6 + + + + + relativeToGround + + + relativeToGround + -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8000000000002 -4.16618075,52.8389800201,1828.8000000000002 -4.16618075,52.8389800201,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8000000000002 -4.1608972222,52.8409833333,1828.8000000000002 -4.1608972222,52.8409833333,609.6 + + + + + + + EGD217I LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8940" txt_name="LLANBEDR"><tr><td>524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>524617N 0040510W -<br/>524603N 0040510W -<br/>523933N 0041231W -<br/>524222N 0041917W -<br/>524942N 0041102W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.183775,52.8282916667,1828.8000000000002 -4.3215111111,52.7062027778,1828.8000000000002 -4.2084722222,52.6592083333,1828.8000000000002 -4.0860444444,52.7675166667,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.0913798344,52.7692187011,1828.8000000000002 -4.0968320407,52.7674020804,1828.8000000000002 -4.1025326866,52.7658921562,1828.8000000000002 -4.1084350162,52.7647013069,1828.8000000000002 -4.1144906333,52.7638392941,1828.8000000000002 -4.1206498956,52.7633131834,1828.8000000000002 -4.1268623184,52.763127287,1828.8000000000002 -4.1330769853,52.7632831285,1828.8000000000002 -4.1392429612,52.7637794307,1828.8000000000002 -4.145309707,52.7646121256,1828.8000000000002 -4.1512274901,52.7657743881,1828.8000000000002 -4.1569477885,52.7672566908,1828.8000000000002 -4.1624236863,52.7690468821,1828.8000000000002 -4.167610256,52.7711302844,1828.8000000000002 -4.1724649246,52.7734898141,1828.8000000000002 -4.1769478222,52.7761061204,1828.8000000000002 -4.1810221083,52.7789577431,1828.8000000000002 -4.1846542748,52.7820212872,1828.8000000000002 -4.1878144214,52.7852716143,1828.8000000000002 -4.1904765038,52.7886820476,1828.8000000000002 -4.1926185491,52.7922245896,1828.8000000000002 -4.1942228402,52.7958701517,1828.8000000000002 -4.1952760644,52.799588792,1828.8000000000002 -4.1957694276,52.8033499607,1828.8000000000002 -4.1956987304,52.8071227506,1828.8000000000002 -4.195064408,52.8108761513,1828.8000000000002 -4.193871531,52.8145793036,1828.8000000000002 -4.1921297686,52.818201754,1828.8000000000002 -4.1898533133,52.8217137049,1828.8000000000002 -4.1870607687,52.8250862609,1828.8000000000002 -4.183775,52.8282916667,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.183775,52.8282916667,609.6 -4.3215111111,52.7062027778,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.7692187011,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.7658921562,609.6 -4.1084350162,52.7647013069,609.6 -4.1144906333,52.7638392941,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.763127287,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.8108761513,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.818201754,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.8250862609,609.6 -4.183775,52.8282916667,609.6 + + + + + relativeToGround + + + relativeToGround + -4.183775,52.8282916667,609.6 -4.3215111111,52.7062027778,609.6 -4.3215111111,52.7062027778,1828.8000000000002 -4.183775,52.8282916667,1828.8000000000002 -4.183775,52.8282916667,609.6 + + + + + relativeToGround + + + relativeToGround + -4.3215111111,52.7062027778,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8000000000002 -4.3215111111,52.7062027778,1828.8000000000002 -4.3215111111,52.7062027778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.0860444444,52.7675166667,1828.8000000000002 -4.2084722222,52.6592083333,1828.8000000000002 -4.2084722222,52.6592083333,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8000000000002 -4.0860444444,52.7675166667,1828.8000000000002 -4.0860444444,52.7675166667,609.6 + + + + + relativeToGround + + + relativeToGround + -4.086225,52.7713305556,609.6 -4.0913798344,52.7692187011,609.6 -4.0913798344,52.7692187011,1828.8000000000002 -4.086225,52.7713305556,1828.8000000000002 -4.086225,52.7713305556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0913798344,52.7692187011,609.6 -4.0968320407,52.7674020804,609.6 -4.0968320407,52.7674020804,1828.8000000000002 -4.0913798344,52.7692187011,1828.8000000000002 -4.0913798344,52.7692187011,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0968320407,52.7674020804,609.6 -4.1025326866,52.7658921562,609.6 -4.1025326866,52.7658921562,1828.8000000000002 -4.0968320407,52.7674020804,1828.8000000000002 -4.0968320407,52.7674020804,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1025326866,52.7658921562,609.6 -4.1084350162,52.7647013069,609.6 -4.1084350162,52.7647013069,1828.8000000000002 -4.1025326866,52.7658921562,1828.8000000000002 -4.1025326866,52.7658921562,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1084350162,52.7647013069,609.6 -4.1144906333,52.7638392941,609.6 -4.1144906333,52.7638392941,1828.8000000000002 -4.1084350162,52.7647013069,1828.8000000000002 -4.1084350162,52.7647013069,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1144906333,52.7638392941,609.6 -4.1206498956,52.7633131834,609.6 -4.1206498956,52.7633131834,1828.8000000000002 -4.1144906333,52.7638392941,1828.8000000000002 -4.1144906333,52.7638392941,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1206498956,52.7633131834,609.6 -4.1268623184,52.763127287,609.6 -4.1268623184,52.763127287,1828.8000000000002 -4.1206498956,52.7633131834,1828.8000000000002 -4.1206498956,52.7633131834,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1268623184,52.763127287,609.6 -4.1330769853,52.7632831285,609.6 -4.1330769853,52.7632831285,1828.8000000000002 -4.1268623184,52.763127287,1828.8000000000002 -4.1268623184,52.763127287,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.1392429612,52.7637794307,1828.8000000000002 -4.1330769853,52.7632831285,1828.8000000000002 -4.1330769853,52.7632831285,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.145309707,52.7646121256,1828.8000000000002 -4.1392429612,52.7637794307,1828.8000000000002 -4.1392429612,52.7637794307,609.6 + + + + + relativeToGround + + + relativeToGround + -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1512274901,52.7657743881,1828.8000000000002 -4.145309707,52.7646121256,1828.8000000000002 -4.145309707,52.7646121256,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1569477885,52.7672566908,1828.8000000000002 -4.1512274901,52.7657743881,1828.8000000000002 -4.1512274901,52.7657743881,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.1624236863,52.7690468821,1828.8000000000002 -4.1569477885,52.7672566908,1828.8000000000002 -4.1569477885,52.7672566908,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.167610256,52.7711302844,1828.8000000000002 -4.1624236863,52.7690468821,1828.8000000000002 -4.1624236863,52.7690468821,609.6 + + + + + relativeToGround + + + relativeToGround + -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1724649246,52.7734898141,1828.8000000000002 -4.167610256,52.7711302844,1828.8000000000002 -4.167610256,52.7711302844,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1769478222,52.7761061204,1828.8000000000002 -4.1724649246,52.7734898141,1828.8000000000002 -4.1724649246,52.7734898141,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1810221083,52.7789577431,1828.8000000000002 -4.1769478222,52.7761061204,1828.8000000000002 -4.1769478222,52.7761061204,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1846542748,52.7820212872,1828.8000000000002 -4.1810221083,52.7789577431,1828.8000000000002 -4.1810221083,52.7789577431,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1878144214,52.7852716143,1828.8000000000002 -4.1846542748,52.7820212872,1828.8000000000002 -4.1846542748,52.7820212872,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1904765038,52.7886820476,1828.8000000000002 -4.1878144214,52.7852716143,1828.8000000000002 -4.1878144214,52.7852716143,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1926185491,52.7922245896,1828.8000000000002 -4.1904765038,52.7886820476,1828.8000000000002 -4.1904765038,52.7886820476,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1942228402,52.7958701517,1828.8000000000002 -4.1926185491,52.7922245896,1828.8000000000002 -4.1926185491,52.7922245896,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1952760644,52.799588792,1828.8000000000002 -4.1942228402,52.7958701517,1828.8000000000002 -4.1942228402,52.7958701517,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1957694276,52.8033499607,1828.8000000000002 -4.1952760644,52.799588792,1828.8000000000002 -4.1952760644,52.799588792,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.1956987304,52.8071227506,1828.8000000000002 -4.1957694276,52.8033499607,1828.8000000000002 -4.1957694276,52.8033499607,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1956987304,52.8071227506,609.6 -4.195064408,52.8108761513,609.6 -4.195064408,52.8108761513,1828.8000000000002 -4.1956987304,52.8071227506,1828.8000000000002 -4.1956987304,52.8071227506,609.6 + + + + + relativeToGround + + + relativeToGround + -4.195064408,52.8108761513,609.6 -4.193871531,52.8145793036,609.6 -4.193871531,52.8145793036,1828.8000000000002 -4.195064408,52.8108761513,1828.8000000000002 -4.195064408,52.8108761513,609.6 + + + + + relativeToGround + + + relativeToGround + -4.193871531,52.8145793036,609.6 -4.1921297686,52.818201754,609.6 -4.1921297686,52.818201754,1828.8000000000002 -4.193871531,52.8145793036,1828.8000000000002 -4.193871531,52.8145793036,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1921297686,52.818201754,609.6 -4.1898533133,52.8217137049,609.6 -4.1898533133,52.8217137049,1828.8000000000002 -4.1921297686,52.818201754,1828.8000000000002 -4.1921297686,52.818201754,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1898533133,52.8217137049,609.6 -4.1870607687,52.8250862609,609.6 -4.1870607687,52.8250862609,1828.8000000000002 -4.1898533133,52.8217137049,1828.8000000000002 -4.1898533133,52.8217137049,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1870607687,52.8250862609,609.6 -4.183775,52.8282916667,609.6 -4.183775,52.8282916667,1828.8000000000002 -4.1870607687,52.8250862609,1828.8000000000002 -4.1870607687,52.8250862609,609.6 + + + + + + + EGD217J LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8941" txt_name="LLANBEDR"><tr><td>525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to<br/>524333N 0040503W -<br/>525307N 0040530W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.0916888889,52.8851638889,1828.8000000000002 -4.08405,52.7257194444,1828.8000000000002 -4.0755987733,52.7276026422,1828.8000000000002 -4.0673688901,52.7298184726,1828.8000000000002 -4.0593953848,52.7323568761,1828.8000000000002 -4.0517125112,52.7352069624,1828.8000000000002 -4.0443532948,52.738356502,1828.8000000000002 -4.037349392,52.7417919777,1828.8000000000002 -4.030730955,52.7454986418,1828.8000000000002 -4.0245265029,52.7494605784,1828.8000000000002 -4.0187627984,52.7536607714,1828.8000000000002 -4.0134647331,52.7580811762,1828.8000000000002 -4.0086552188,52.7627027967,1828.8000000000002 -4.0043550877,52.7675057658,1828.8000000000002 -4.0005830012,52.7724694303,1828.8000000000002 -3.9973553675,52.7775724392,1828.8000000000002 -3.9946862679,52.7827928341,1828.8000000000002 -3.9925873936,52.7881081439,1828.8000000000002 -3.9910679921,52.7934954808,1828.8000000000002 -3.9901348241,52.7989316381,1828.8000000000002 -3.9897921305,52.8043931904,1828.8000000000002 -3.9900416104,52.8098565941,1828.8000000000002 -3.9908824103,52.8152982887,1828.8000000000002 -3.9923111235,52.8206947986,1828.8000000000002 -3.9943218012,52.8260228348,1828.8000000000002 -3.9969059746,52.831259395,1828.8000000000002 -4.0000526878,52.8363818638,1828.8000000000002 -4.0037485419,52.8413681109,1828.8000000000002 -4.0079777498,52.8461965867,1828.8000000000002 -4.0127222017,52.8508464167,1828.8000000000002 -4.0179615407,52.8552974922,1828.8000000000002 -4.0236732496,52.8595305579,1828.8000000000002 -4.0298327457,52.8635272962,1828.8000000000002 -4.0364134868,52.8672704074,1828.8000000000002 -4.0433870849,52.8707436851,1828.8000000000002 -4.0507234291,52.8739320877,1828.8000000000002 -4.0583908159,52.8768218039,1828.8000000000002 -4.0663560872,52.8794003139,1828.8000000000002 -4.0745847751,52.8816564439,1828.8000000000002 -4.0830412523,52.8835804155,1828.8000000000002 -4.0916888889,52.8851638889,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.0916888889,52.8851638889,609.6 -4.08405,52.7257194444,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.7580811762,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.7827928341,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.7934954808,609.6 -3.9901348241,52.7989316381,609.6 -3.9897921305,52.8043931904,609.6 -3.9900416104,52.8098565941,609.6 -3.9908824103,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.8508464167,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0916888889,52.8851638889,609.6 -4.08405,52.7257194444,609.6 -4.08405,52.7257194444,1828.8000000000002 -4.0916888889,52.8851638889,1828.8000000000002 -4.0916888889,52.8851638889,609.6 + + + + + relativeToGround + + + relativeToGround + -4.08405,52.7257194444,609.6 -4.0755987733,52.7276026422,609.6 -4.0755987733,52.7276026422,1828.8000000000002 -4.08405,52.7257194444,1828.8000000000002 -4.08405,52.7257194444,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0673688901,52.7298184726,1828.8000000000002 -4.0755987733,52.7276026422,1828.8000000000002 -4.0755987733,52.7276026422,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0593953848,52.7323568761,1828.8000000000002 -4.0673688901,52.7298184726,1828.8000000000002 -4.0673688901,52.7298184726,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0517125112,52.7352069624,1828.8000000000002 -4.0593953848,52.7323568761,1828.8000000000002 -4.0593953848,52.7323568761,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.0443532948,52.738356502,1828.8000000000002 -4.0517125112,52.7352069624,1828.8000000000002 -4.0517125112,52.7352069624,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.037349392,52.7417919777,1828.8000000000002 -4.0443532948,52.738356502,1828.8000000000002 -4.0443532948,52.738356502,609.6 + + + + + relativeToGround + + + relativeToGround + -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.030730955,52.7454986418,1828.8000000000002 -4.037349392,52.7417919777,1828.8000000000002 -4.037349392,52.7417919777,609.6 + + + + + relativeToGround + + + relativeToGround + -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0245265029,52.7494605784,1828.8000000000002 -4.030730955,52.7454986418,1828.8000000000002 -4.030730955,52.7454986418,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0187627984,52.7536607714,1828.8000000000002 -4.0245265029,52.7494605784,1828.8000000000002 -4.0245265029,52.7494605784,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0187627984,52.7536607714,609.6 -4.0134647331,52.7580811762,609.6 -4.0134647331,52.7580811762,1828.8000000000002 -4.0187627984,52.7536607714,1828.8000000000002 -4.0187627984,52.7536607714,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0134647331,52.7580811762,609.6 -4.0086552188,52.7627027967,609.6 -4.0086552188,52.7627027967,1828.8000000000002 -4.0134647331,52.7580811762,1828.8000000000002 -4.0134647331,52.7580811762,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0043550877,52.7675057658,1828.8000000000002 -4.0086552188,52.7627027967,1828.8000000000002 -4.0086552188,52.7627027967,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -4.0005830012,52.7724694303,1828.8000000000002 -4.0043550877,52.7675057658,1828.8000000000002 -4.0043550877,52.7675057658,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9973553675,52.7775724392,1828.8000000000002 -4.0005830012,52.7724694303,1828.8000000000002 -4.0005830012,52.7724694303,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9973553675,52.7775724392,609.6 -3.9946862679,52.7827928341,609.6 -3.9946862679,52.7827928341,1828.8000000000002 -3.9973553675,52.7775724392,1828.8000000000002 -3.9973553675,52.7775724392,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9946862679,52.7827928341,609.6 -3.9925873936,52.7881081439,609.6 -3.9925873936,52.7881081439,1828.8000000000002 -3.9946862679,52.7827928341,1828.8000000000002 -3.9946862679,52.7827928341,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9925873936,52.7881081439,609.6 -3.9910679921,52.7934954808,609.6 -3.9910679921,52.7934954808,1828.8000000000002 -3.9925873936,52.7881081439,1828.8000000000002 -3.9925873936,52.7881081439,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9910679921,52.7934954808,609.6 -3.9901348241,52.7989316381,609.6 -3.9901348241,52.7989316381,1828.8000000000002 -3.9910679921,52.7934954808,1828.8000000000002 -3.9910679921,52.7934954808,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9901348241,52.7989316381,609.6 -3.9897921305,52.8043931904,609.6 -3.9897921305,52.8043931904,1828.8000000000002 -3.9901348241,52.7989316381,1828.8000000000002 -3.9901348241,52.7989316381,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9897921305,52.8043931904,609.6 -3.9900416104,52.8098565941,609.6 -3.9900416104,52.8098565941,1828.8000000000002 -3.9897921305,52.8043931904,1828.8000000000002 -3.9897921305,52.8043931904,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9900416104,52.8098565941,609.6 -3.9908824103,52.8152982887,609.6 -3.9908824103,52.8152982887,1828.8000000000002 -3.9900416104,52.8098565941,1828.8000000000002 -3.9900416104,52.8098565941,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9908824103,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9923111235,52.8206947986,1828.8000000000002 -3.9908824103,52.8152982887,1828.8000000000002 -3.9908824103,52.8152982887,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9943218012,52.8260228348,1828.8000000000002 -3.9923111235,52.8206947986,1828.8000000000002 -3.9923111235,52.8206947986,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -3.9969059746,52.831259395,1828.8000000000002 -3.9943218012,52.8260228348,1828.8000000000002 -3.9943218012,52.8260228348,609.6 + + + + + relativeToGround + + + relativeToGround + -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0000526878,52.8363818638,1828.8000000000002 -3.9969059746,52.831259395,1828.8000000000002 -3.9969059746,52.831259395,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0037485419,52.8413681109,1828.8000000000002 -4.0000526878,52.8363818638,1828.8000000000002 -4.0000526878,52.8363818638,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0079777498,52.8461965867,1828.8000000000002 -4.0037485419,52.8413681109,1828.8000000000002 -4.0037485419,52.8413681109,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0079777498,52.8461965867,609.6 -4.0127222017,52.8508464167,609.6 -4.0127222017,52.8508464167,1828.8000000000002 -4.0079777498,52.8461965867,1828.8000000000002 -4.0079777498,52.8461965867,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0127222017,52.8508464167,609.6 -4.0179615407,52.8552974922,609.6 -4.0179615407,52.8552974922,1828.8000000000002 -4.0127222017,52.8508464167,1828.8000000000002 -4.0127222017,52.8508464167,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0236732496,52.8595305579,1828.8000000000002 -4.0179615407,52.8552974922,1828.8000000000002 -4.0179615407,52.8552974922,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0298327457,52.8635272962,1828.8000000000002 -4.0236732496,52.8595305579,1828.8000000000002 -4.0236732496,52.8595305579,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0364134868,52.8672704074,1828.8000000000002 -4.0298327457,52.8635272962,1828.8000000000002 -4.0298327457,52.8635272962,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0433870849,52.8707436851,1828.8000000000002 -4.0364134868,52.8672704074,1828.8000000000002 -4.0364134868,52.8672704074,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0507234291,52.8739320877,1828.8000000000002 -4.0433870849,52.8707436851,1828.8000000000002 -4.0433870849,52.8707436851,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0583908159,52.8768218039,1828.8000000000002 -4.0507234291,52.8739320877,1828.8000000000002 -4.0507234291,52.8739320877,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0663560872,52.8794003139,1828.8000000000002 -4.0583908159,52.8768218039,1828.8000000000002 -4.0583908159,52.8768218039,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0745847751,52.8816564439,1828.8000000000002 -4.0663560872,52.8794003139,1828.8000000000002 -4.0663560872,52.8794003139,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0830412523,52.8835804155,1828.8000000000002 -4.0745847751,52.8816564439,1828.8000000000002 -4.0745847751,52.8816564439,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8000000000002 -4.0830412523,52.8835804155,1828.8000000000002 -4.0830412523,52.8835804155,609.6 + + + + + + + EGD217K LLANBEDR + <table border="1" cellpadding="1" cellspacing="0" row_id="8942" txt_name="LLANBEDR"><tr><td>525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to<br/>525307N 0040530W -<br/>525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to<br/>525028N 0040939W -<br/>525306N 0040947W <br/>Upper limit: 6000 FT MSL<br/>Lower limit: 2000 FT MSL<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.<br/><br/>Service: SUAAIS Llanbedr Information on 118.930 MHz.<br/><br/>Contact: Llanbedr Information, Tel: 01341-241356.<br/><br/>Danger Area Authority: Snowdonia Aerospace.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,1828.8000000000002 -4.1608972222,52.8409833333,1828.8000000000002 -4.1553132526,52.8426949429,1828.8000000000002 -4.149494417,52.8440909498,1828.8000000000002 -4.143489638,52.8451603374,1828.8000000000002 -4.1373488445,52.8458942118,1828.8000000000002 -4.131123106,52.8462864694,1828.8000000000002 -4.1248642045,52.8463338475,1828.8000000000002 -4.1186242003,52.8460359521,1828.8000000000002 -4.1124549952,52.8453952609,1828.8000000000002 -4.1064078968,52.8444171027,1828.8000000000002 -4.100533189,52.8431096128,1828.8000000000002 -4.0948797102,52.8414836643,1828.8000000000002 -4.0894944444,52.8395527778,1828.8000000000002 -4.0916888889,52.8851638889,1828.8000000000002 -4.1004821132,52.886398031,1828.8000000000002 -4.1093902725,52.8872810751,1828.8000000000002 -4.118375237,52.8878082526,1828.8000000000002 -4.1273981205,52.8879772819,1828.8000000000002 -4.13641987,52.8877874313,1828.8000000000002 -4.1454014374,52.8872395227,1828.8000000000002 -4.1543039514,52.8863359272,1828.8000000000002 -4.1630888889,52.8850805556,1828.8000000000002 + + + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.8462864694,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.886398031,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.8879772819,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.8872395227,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8000000000002 -4.1630888889,52.8850805556,1828.8000000000002 -4.1630888889,52.8850805556,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.1553132526,52.8426949429,1828.8000000000002 -4.1608972222,52.8409833333,1828.8000000000002 -4.1608972222,52.8409833333,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.149494417,52.8440909498,1828.8000000000002 -4.1553132526,52.8426949429,1828.8000000000002 -4.1553132526,52.8426949429,609.6 + + + + + relativeToGround + + + relativeToGround + -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.143489638,52.8451603374,1828.8000000000002 -4.149494417,52.8440909498,1828.8000000000002 -4.149494417,52.8440909498,609.6 + + + + + relativeToGround + + + relativeToGround + -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.1373488445,52.8458942118,1828.8000000000002 -4.143489638,52.8451603374,1828.8000000000002 -4.143489638,52.8451603374,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1373488445,52.8458942118,609.6 -4.131123106,52.8462864694,609.6 -4.131123106,52.8462864694,1828.8000000000002 -4.1373488445,52.8458942118,1828.8000000000002 -4.1373488445,52.8458942118,609.6 + + + + + relativeToGround + + + relativeToGround + -4.131123106,52.8462864694,609.6 -4.1248642045,52.8463338475,609.6 -4.1248642045,52.8463338475,1828.8000000000002 -4.131123106,52.8462864694,1828.8000000000002 -4.131123106,52.8462864694,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1186242003,52.8460359521,1828.8000000000002 -4.1248642045,52.8463338475,1828.8000000000002 -4.1248642045,52.8463338475,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1124549952,52.8453952609,1828.8000000000002 -4.1186242003,52.8460359521,1828.8000000000002 -4.1186242003,52.8460359521,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.1064078968,52.8444171027,1828.8000000000002 -4.1124549952,52.8453952609,1828.8000000000002 -4.1124549952,52.8453952609,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.100533189,52.8431096128,1828.8000000000002 -4.1064078968,52.8444171027,1828.8000000000002 -4.1064078968,52.8444171027,609.6 + + + + + relativeToGround + + + relativeToGround + -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0948797102,52.8414836643,1828.8000000000002 -4.100533189,52.8431096128,1828.8000000000002 -4.100533189,52.8431096128,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8000000000002 -4.0948797102,52.8414836643,1828.8000000000002 -4.0948797102,52.8414836643,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8000000000002 -4.0894944444,52.8395527778,1828.8000000000002 -4.0894944444,52.8395527778,609.6 + + + + + relativeToGround + + + relativeToGround + -4.0916888889,52.8851638889,609.6 -4.1004821132,52.886398031,609.6 -4.1004821132,52.886398031,1828.8000000000002 -4.0916888889,52.8851638889,1828.8000000000002 -4.0916888889,52.8851638889,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1004821132,52.886398031,609.6 -4.1093902725,52.8872810751,609.6 -4.1093902725,52.8872810751,1828.8000000000002 -4.1004821132,52.886398031,1828.8000000000002 -4.1004821132,52.886398031,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.118375237,52.8878082526,1828.8000000000002 -4.1093902725,52.8872810751,1828.8000000000002 -4.1093902725,52.8872810751,609.6 + + + + + relativeToGround + + + relativeToGround + -4.118375237,52.8878082526,609.6 -4.1273981205,52.8879772819,609.6 -4.1273981205,52.8879772819,1828.8000000000002 -4.118375237,52.8878082526,1828.8000000000002 -4.118375237,52.8878082526,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1273981205,52.8879772819,609.6 -4.13641987,52.8877874313,609.6 -4.13641987,52.8877874313,1828.8000000000002 -4.1273981205,52.8879772819,1828.8000000000002 -4.1273981205,52.8879772819,609.6 + + + + + relativeToGround + + + relativeToGround + -4.13641987,52.8877874313,609.6 -4.1454014374,52.8872395227,609.6 -4.1454014374,52.8872395227,1828.8000000000002 -4.13641987,52.8877874313,1828.8000000000002 -4.13641987,52.8877874313,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1454014374,52.8872395227,609.6 -4.1543039514,52.8863359272,609.6 -4.1543039514,52.8863359272,1828.8000000000002 -4.1454014374,52.8872395227,1828.8000000000002 -4.1454014374,52.8872395227,609.6 + + + + + relativeToGround + + + relativeToGround + -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8000000000002 -4.1543039514,52.8863359272,1828.8000000000002 -4.1543039514,52.8863359272,609.6 + + + + + + + EGD218A FAIRFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14485" txt_name="FAIRFORD"><tr><td>514815N 0013543W -<br/>514016N 0013518W -<br/>513958N 0014917W -<br/>514110N 0015928W -<br/>514744N 0015952W -<br/>514815N 0013543W <br/>Upper limit: FL75<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).<br/><br/>Service: SUACS: Brize Radar on 124.275 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5951848611,51.80407725,2286.0 -1.9976505556,51.7955109722,2286.0 -1.9911186944,51.6860482222,2286.0 -1.8215250833,51.6661864444,2286.0 -1.58842725,51.6709806111,2286.0 -1.5951848611,51.80407725,2286.0 + + + + + + EGD218B FAIRFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14481" txt_name="FAIRFORD"><tr><td>520518N 0020404W -<br/>514803N 0014539W -<br/>514749N 0015601W -<br/>514901N 0020407W -<br/>515342N 0022132W -<br/>520518N 0020404W <br/>Upper limit: FL240<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).<br/><br/>Service: SUACS: Below FL160 Brize Radar on 124.275 MHz. At/above FL160 Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.0679103333,52.0883218333,7315.2 -2.3588221389,51.8948650833,7315.2 -2.0686747222,51.8169415833,7315.2 -1.9337063889,51.7969642778,7315.2 -1.76084275,51.8007185,7315.2 -2.0679103333,52.0883218333,7315.2 + + + + + relativeToGround + + + relativeToGround + -2.0679103333,52.0883218333,1524.0 -2.3588221389,51.8948650833,1524.0 -2.0686747222,51.8169415833,1524.0 -1.9337063889,51.7969642778,1524.0 -1.76084275,51.8007185,1524.0 -2.0679103333,52.0883218333,1524.0 + + + + + relativeToGround + + + relativeToGround + -2.0679103333,52.0883218333,1524.0 -2.3588221389,51.8948650833,1524.0 -2.3588221389,51.8948650833,7315.2 -2.0679103333,52.0883218333,7315.2 -2.0679103333,52.0883218333,1524.0 + + + + + relativeToGround + + + relativeToGround + -2.3588221389,51.8948650833,1524.0 -2.0686747222,51.8169415833,1524.0 -2.0686747222,51.8169415833,7315.2 -2.3588221389,51.8948650833,7315.2 -2.3588221389,51.8948650833,1524.0 + + + + + relativeToGround + + + relativeToGround + -2.0686747222,51.8169415833,1524.0 -1.9337063889,51.7969642778,1524.0 -1.9337063889,51.7969642778,7315.2 -2.0686747222,51.8169415833,7315.2 -2.0686747222,51.8169415833,1524.0 + + + + + relativeToGround + + + relativeToGround + -1.9337063889,51.7969642778,1524.0 -1.76084275,51.8007185,1524.0 -1.76084275,51.8007185,7315.2 -1.9337063889,51.7969642778,7315.2 -1.9337063889,51.7969642778,1524.0 + + + + + relativeToGround + + + relativeToGround + -1.76084275,51.8007185,1524.0 -2.0679103333,52.0883218333,1524.0 -2.0679103333,52.0883218333,7315.2 -1.76084275,51.8007185,7315.2 -1.76084275,51.8007185,1524.0 + + + + + + + EGD218C FAIRFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14479" txt_name="FAIRFORD"><tr><td>521533N 0021510W -<br/>520518N 0020404W -<br/>515342N 0022132W -<br/>515701N 0023402W -<br/>520117N 0023842W -<br/>521533N 0021510W <br/>Upper limit: FL660<br/>Lower limit: FL160<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).<br/><br/>Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.2526999167,52.2592760556,20116.8 -2.6449074167,52.0214293333,20116.8 -2.567252,51.9502352778,20116.8 -2.3588221389,51.8948650833,20116.8 -2.0679103333,52.0883218333,20116.8 -2.2526999167,52.2592760556,20116.8 + + + + + relativeToGround + + + relativeToGround + -2.2526999167,52.2592760556,4876.8 -2.6449074167,52.0214293333,4876.8 -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.2592760556,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.2526999167,52.2592760556,4876.8 -2.6449074167,52.0214293333,4876.8 -2.6449074167,52.0214293333,20116.8 -2.2526999167,52.2592760556,20116.8 -2.2526999167,52.2592760556,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.6449074167,52.0214293333,4876.8 -2.567252,51.9502352778,4876.8 -2.567252,51.9502352778,20116.8 -2.6449074167,52.0214293333,20116.8 -2.6449074167,52.0214293333,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.3588221389,51.8948650833,20116.8 -2.567252,51.9502352778,20116.8 -2.567252,51.9502352778,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.0679103333,52.0883218333,20116.8 -2.3588221389,51.8948650833,20116.8 -2.3588221389,51.8948650833,4876.8 + + + + + relativeToGround + + + relativeToGround + -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.2592760556,4876.8 -2.2526999167,52.2592760556,20116.8 -2.0679103333,52.0883218333,20116.8 -2.0679103333,52.0883218333,4876.8 + + + + + + + EGD218D FAIRFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14482" txt_name="FAIRFORD"><tr><td>523258N 0023414W -<br/>521533N 0021510W -<br/>520117N 0023842W -<br/>521342N 0025221W -<br/>522607N 0025118W -<br/>523258N 0023414W <br/>Upper limit: FL660<br/>Lower limit: FL200<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).<br/><br/>Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.5705153611,52.5495711667,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8724085833,52.2284006944,20116.8 -2.6449074167,52.0214293333,20116.8 -2.2526999167,52.2592760556,20116.8 -2.5705153611,52.5495711667,20116.8 + + + + + relativeToGround + + + relativeToGround + -2.5705153611,52.5495711667,6096.0 -2.8549897222,52.4352228333,6096.0 -2.8724085833,52.2284006944,6096.0 -2.6449074167,52.0214293333,6096.0 -2.2526999167,52.2592760556,6096.0 -2.5705153611,52.5495711667,6096.0 + + + + + relativeToGround + + + relativeToGround + -2.5705153611,52.5495711667,6096.0 -2.8549897222,52.4352228333,6096.0 -2.8549897222,52.4352228333,20116.8 -2.5705153611,52.5495711667,20116.8 -2.5705153611,52.5495711667,6096.0 + + + + + relativeToGround + + + relativeToGround + -2.8549897222,52.4352228333,6096.0 -2.8724085833,52.2284006944,6096.0 -2.8724085833,52.2284006944,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8549897222,52.4352228333,6096.0 + + + + + relativeToGround + + + relativeToGround + -2.8724085833,52.2284006944,6096.0 -2.6449074167,52.0214293333,6096.0 -2.6449074167,52.0214293333,20116.8 -2.8724085833,52.2284006944,20116.8 -2.8724085833,52.2284006944,6096.0 + + + + + relativeToGround + + + relativeToGround + -2.6449074167,52.0214293333,6096.0 -2.2526999167,52.2592760556,6096.0 -2.2526999167,52.2592760556,20116.8 -2.6449074167,52.0214293333,20116.8 -2.6449074167,52.0214293333,6096.0 + + + + + relativeToGround + + + relativeToGround + -2.2526999167,52.2592760556,6096.0 -2.5705153611,52.5495711667,6096.0 -2.5705153611,52.5495711667,20116.8 -2.2526999167,52.2592760556,20116.8 -2.2526999167,52.2592760556,6096.0 + + + + + + + EGD304 UPPER HULME + <table border="1" cellpadding="1" cellspacing="0" row_id="1003" txt_name="UPPER HULME"><tr><td>A circle, 1.5 NM radius, centred at 530951N 0015730W <br/>Upper limit: 3500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Manchester APP on 118.580 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.<br/><br/>Remarks: SI 1985/1082.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9583333333,53.1891285695,1066.8 -1.9632487194,53.1889532633,1066.8 -1.9680949854,53.1884298098,1066.8 -1.9728039882,53.1875655697,1066.8 -1.9773095245,53.1863726948,1066.8 -1.9815482657,53.1848679569,1066.8 -1.9854606515,53.1830725106,1066.8 -1.9889917292,53.1810115942,1066.8 -1.9920919267,53.1787141743,1066.8 -1.994717749,53.1762125364,1066.8 -1.9968323868,53.1735418303,1066.8 -1.9984062307,53.1707395745,1066.8 -1.9994172825,53.1678451281,1066.8 -1.9998514587,53.1648991371,1066.8 -1.9997027821,53.1619429631,1066.8 -1.9989734591,53.159018102,1066.8 -1.9976738419,53.1561656021,1066.8 -1.995822277,53.1534254881,1066.8 -1.9934448418,53.1508362003,1066.8 -1.990574974,53.1484340564,1066.8 -1.9872529981,53.1462527437,1066.8 -1.983525558,53.1443228474,1066.8 -1.9794449609,53.1426714238,1066.8 -1.9750684446,53.1413216224,1066.8 -1.9704573761,53.1402923625,1066.8 -1.9656763943,53.1395980694,1066.8 -1.9607925076,53.1392484733,1066.8 -1.9558741591,53.1392484733,1066.8 -1.9509902724,53.1395980694,1066.8 -1.9462092906,53.1402923625,1066.8 -1.9415982221,53.1413216224,1066.8 -1.9372217058,53.1426714238,1066.8 -1.9331411087,53.1443228474,1066.8 -1.9294136686,53.1462527437,1066.8 -1.9260916927,53.1484340564,1066.8 -1.9232218248,53.1508362003,1066.8 -1.9208443897,53.1534254881,1066.8 -1.9189928248,53.1561656021,1066.8 -1.9176932075,53.159018102,1066.8 -1.9169638845,53.1619429631,1066.8 -1.916815208,53.1648991371,1066.8 -1.9172493842,53.1678451281,1066.8 -1.918260436,53.1707395745,1066.8 -1.9198342799,53.1735418303,1066.8 -1.9219489177,53.1762125364,1066.8 -1.9245747399,53.1787141743,1066.8 -1.9276749375,53.1810115942,1066.8 -1.9312060152,53.1830725106,1066.8 -1.935118401,53.1848679569,1066.8 -1.9393571422,53.1863726948,1066.8 -1.9438626785,53.1875655697,1066.8 -1.9485716812,53.1884298098,1066.8 -1.9534179472,53.1889532633,1066.8 -1.9583333333,53.1891285695,1066.8 + + + + + + EGD305 BECKINGHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="1004" txt_name="BECKINGHAM"><tr><td>530554N 0004134W -<br/>530542N 0004034W -<br/>530427N 0004044W -<br/>530428N 0004205W -<br/>530534N 0004217W -<br/>530554N 0004134W <br/>Upper limit: 1500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 07769-730481.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6927777778,53.0983333333,457.20000000000005 -0.7047222222,53.0927777778,457.20000000000005 -0.7013888889,53.0744444444,457.20000000000005 -0.6788888889,53.0741666667,457.20000000000005 -0.6761111111,53.095,457.20000000000005 -0.6927777778,53.0983333333,457.20000000000005 + + + + + + EGD307 DONNA NOOK + <table border="1" cellpadding="1" cellspacing="0" row_id="1005" txt_name="DONNA NOOK"><tr><td>532331N 0001354E -<br/>532932N 0000503E thence clockwise by the arc of a circle radius 5 NM centred on 532830N 0001315E to -<br/>532331N 0001354E <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 20,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Donna Nook Range on 122.750 MHz when open. SUAAIS: Donna Nook Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01507-359126.<br/><br/>Remarks: Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Holbeach and Pembrey AWRs. Ensure crossing clearance request is specific to Donna Nook AWR. SI 1939/451. UAS BVLOS will not be conducted above 12,000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.2316666667,53.3919444444,7010.400000000001 0.2406825788,53.3925294729,7010.400000000001 0.2496135246,53.3934738632,7010.400000000001 0.2584233162,53.3947627808,7010.400000000001 0.2670748532,53.3963907993,7010.400000000001 0.2755316902,53.398351064,7010.400000000001 0.283758188,53.4006353204,7010.400000000001 0.2917196616,53.4032339479,7010.400000000001 0.299382525,53.4061360005,7010.400000000001 0.3067144306,53.4093292513,7010.400000000001 0.3136844052,53.4128002441,7010.400000000001 0.3202629797,53.4165343486,7010.400000000001 0.3264223132,53.4205158216,7010.400000000001 0.3321363105,53.4247278727,7010.400000000001 0.3373807333,53.4291527337,7010.400000000001 0.3421333029,53.4337717333,7010.400000000001 0.3463737964,53.4385653748,7010.400000000001 0.3500841336,53.4435134178,7010.400000000001 0.353248456,53.4485949627,7010.400000000001 0.3558531959,53.4537885386,7010.400000000001 0.3578871374,53.4590721933,7010.400000000001 0.3593414664,53.4644235858,7010.400000000001 0.3602098119,53.4698200802,7010.400000000001 0.360488276,53.4752388414,7010.400000000001 0.3601754547,53.4806569311,7010.400000000001 0.3592724472,53.4860514054,7010.400000000001 0.3577828553,53.4913994117,7010.400000000001 0.3557127719,53.4966782858,7010.400000000001 0.3530707587,53.501865648,7010.400000000001 0.3498678134,53.5069394986,7010.400000000001 0.3461173266,53.5118783116,7010.400000000001 0.3418350278,53.5166611264,7010.400000000001 0.3370389214,53.5212676377,7010.400000000001 0.3317492124,53.5256782822,7010.400000000001 0.3259882231,53.5298743225,7010.400000000001 0.3197802995,53.5338379274,7010.400000000001 0.313151709,53.5375522487,7010.400000000001 0.3061305297,53.5410014936,7010.400000000001 0.2987465312,53.5441709927,7010.400000000001 0.2910310476,53.5470472631,7010.400000000001 0.2830168442,53.5496180668,7010.400000000001 0.2747379765,53.5518724632,7010.400000000001 0.2662296443,53.5538008569,7010.400000000001 0.2575280401,53.5553950386,7010.400000000001 0.2486701928,53.556648221,7010.400000000001 0.2396938079,53.5575550683,7010.400000000001 0.2306371044,53.5581117187,7010.400000000001 0.2215386491,53.5583158018,7010.400000000001 0.2124371901,53.5581664484,7010.400000000001 0.2033714882,53.5576642946,7010.400000000001 0.1943801493,53.5568114788,7010.400000000001 0.1855014572,53.5556116326,7010.400000000001 0.1767732078,53.554069865,7010.400000000001 0.1682325452,53.5521927402,7010.400000000001 0.1599158018,53.5499882492,7010.400000000001 0.1518583412,53.5474657756,7010.400000000001 0.144094406,53.5446360542,7010.400000000001 0.1366569705,53.5415111256,7010.400000000001 0.1295775996,53.5381042833,7010.400000000001 0.1228863138,53.5344300172,7010.400000000001 0.116611461,53.5305039502,7010.400000000001 0.1107795966,53.5263427719,7010.400000000001 0.1054153713,53.5219641659,7010.400000000001 0.1005414271,53.5173867345,7010.400000000001 0.0961783027,53.5126299184,7010.400000000001 0.0923443485,53.5077139136,7010.400000000001 0.0890556509,53.5026595851,7010.400000000001 0.0863259664,53.4974883771,7010.400000000001 0.0841666667,53.4922222222,7010.400000000001 0.2316666667,53.3919444444,7010.400000000001 + + + + + + EGD314 HARPUR HILL + <table border="1" cellpadding="1" cellspacing="0" row_id="1630" txt_name="HARPUR HILL"><tr><td>A circle, 0.5 NM radius, centred at 531343N 0015528W <br/>Upper limit: 2900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Manchester APP on 118.580 MHz.<br/><br/>Contact: HSE (The Health and Safety Executive), Tel: 0203-028 2000.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9244444444,53.2369316665,883.9200000000001 -1.9272361795,53.2367613117,883.9200000000001 -1.9299135563,53.2362572255,883.9200000000001 -1.932366909,53.2354400564,883.9200000000001 -1.9344957623,53.2343432761,883.9200000000001 -1.9362129508,53.233011806,883.9200000000001 -1.9374481891,53.2315001758,883.9200000000001 -1.9381509465,53.2298702871,883.9200000000001 -1.9382925095,53.2281888772,883.9200000000001 -1.9378671475,53.2265247852,883.9200000000001 -1.9368923376,53.2249461335,883.9200000000001 -1.9354080383,53.2235175393,883.9200000000001 -1.9334750457,53.2222974722,883.9200000000001 -1.9311725002,53.2213358622,883.9200000000001 -1.9285946453,53.2206720594,883.9200000000001 -1.9258469737,53.2203332259,883.9200000000001 -1.9230419152,53.2203332259,883.9200000000001 -1.9202942436,53.2206720594,883.9200000000001 -1.9177163887,53.2213358622,883.9200000000001 -1.9154138432,53.2222974722,883.9200000000001 -1.9134808506,53.2235175393,883.9200000000001 -1.9119965513,53.2249461335,883.9200000000001 -1.9110217413,53.2265247852,883.9200000000001 -1.9105963794,53.2281888772,883.9200000000001 -1.9107379424,53.2298702871,883.9200000000001 -1.9114406998,53.2315001758,883.9200000000001 -1.9126759381,53.233011806,883.9200000000001 -1.9143931266,53.2343432761,883.9200000000001 -1.9165219799,53.2354400564,883.9200000000001 -1.9189753326,53.2362572255,883.9200000000001 -1.9216527094,53.2367613117,883.9200000000001 -1.9244444444,53.2369316665,883.9200000000001 + + + + + + EGD323A SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1006" txt_name="SOUTHERN COMPLEX"><tr><td>551710N 0001428E -<br/>550143N 0011753E -<br/>543102N 0003132W -<br/>544841N 0005456W -<br/>545744N 0005457W -<br/>551710N 0001428E <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 0.2412277778,55.2861722222,20116.8 -0.9158333333,54.9623333333,20116.8 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 + + + + + relativeToGround + + + relativeToGround + 0.2412277778,55.2861722222,1524.0 -0.9158333333,54.9623333333,1524.0 -0.9156,54.8112972222,1524.0 -0.5256138889,54.5171138889,1524.0 1.298075,55.0285222222,1524.0 0.2412277778,55.2861722222,1524.0 + + + + + relativeToGround + + + relativeToGround + 0.2412277778,55.2861722222,1524.0 -0.9158333333,54.9623333333,1524.0 -0.9158333333,54.9623333333,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.9158333333,54.9623333333,1524.0 -0.9156,54.8112972222,1524.0 -0.9156,54.8112972222,20116.8 -0.9158333333,54.9623333333,20116.8 -0.9158333333,54.9623333333,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.9156,54.8112972222,1524.0 -0.5256138889,54.5171138889,1524.0 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,1524.0 1.298075,55.0285222222,1524.0 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524.0 + + + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,1524.0 0.2412277778,55.2861722222,1524.0 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524.0 + + + + + + + EGD323B SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1007" txt_name="SOUTHERN COMPLEX"><tr><td>550143N 0011753E -<br/>545059N 0020010E -<br/>541451N 0001028W -<br/>543102N 0003132W -<br/>550143N 0011753E <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 + + + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,1524.0 -0.5256138889,54.5171138889,1524.0 -0.1744611111,54.24745,1524.0 2.0026916667,54.8496888889,1524.0 1.298075,55.0285222222,1524.0 + + + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,1524.0 -0.5256138889,54.5171138889,1524.0 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,1524.0 -0.1744611111,54.24745,1524.0 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,1524.0 2.0026916667,54.8496888889,1524.0 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,1524.0 1.298075,55.0285222222,1524.0 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524.0 + + + + + + + EGD323C SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1008" txt_name="SOUTHERN COMPLEX"><tr><td>545059N 0020010E -<br/>544532N 0022109E -<br/>540644N 0000002W -<br/>541451N 0001028W -<br/>545059N 0020010E <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -5.361111E-4,54.1121805556,20116.8 2.3526361111,54.75875,20116.8 2.0026916667,54.8496888889,20116.8 + + + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,1524.0 -0.1744611111,54.24745,1524.0 -5.361111E-4,54.1121805556,1524.0 2.3526361111,54.75875,1524.0 2.0026916667,54.8496888889,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,1524.0 -0.1744611111,54.24745,1524.0 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524.0 + + + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,1524.0 -5.361111E-4,54.1121805556,1524.0 -5.361111E-4,54.1121805556,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,1524.0 2.3526361111,54.75875,1524.0 2.3526361111,54.75875,20116.8 -5.361111E-4,54.1121805556,20116.8 -5.361111E-4,54.1121805556,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,1524.0 2.0026916667,54.8496888889,1524.0 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875,20116.8 2.3526361111,54.75875,1524.0 + + + + + + + EGD323D SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1009" txt_name="SOUTHERN COMPLEX"><tr><td>544532N 0022109E -<br/>543948N 0024252E -<br/>543143N 0025434E -<br/>541738N 0030110E -<br/>533813N 0003557E -<br/>540644N 0000002W -<br/>544532N 0022109E <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,20116.8 -5.361111E-4,54.1121805556,20116.8 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875,20116.8 + + + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,1524.0 -5.361111E-4,54.1121805556,1524.0 0.599175,53.6369388889,1524.0 3.0193416667,54.2940166667,1524.0 2.9095444444,54.5285361111,1524.0 2.7144361111,54.6632333333,1524.0 2.3526361111,54.75875,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,1524.0 -5.361111E-4,54.1121805556,1524.0 -5.361111E-4,54.1121805556,20116.8 2.3526361111,54.75875,20116.8 2.3526361111,54.75875,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,1524.0 0.599175,53.6369388889,1524.0 0.599175,53.6369388889,20116.8 -5.361111E-4,54.1121805556,20116.8 -5.361111E-4,54.1121805556,1524.0 + + + + + relativeToGround + + + relativeToGround + 0.599175,53.6369388889,1524.0 3.0193416667,54.2940166667,1524.0 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524.0 + + + + + relativeToGround + + + relativeToGround + 3.0193416667,54.2940166667,1524.0 2.9095444444,54.5285361111,1524.0 2.9095444444,54.5285361111,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.9095444444,54.5285361111,1524.0 2.7144361111,54.6632333333,1524.0 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.7144361111,54.6632333333,1524.0 2.3526361111,54.75875,1524.0 2.3526361111,54.75875,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,1524.0 + + + + + + + EGD323E SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1010" txt_name="SOUTHERN COMPLEX"><tr><td>541738N 0030110E -<br/>541733N 0030112E -<br/>535535N 0025714E -<br/>532807N 0024241E -<br/>533813N 0003557E -<br/>541738N 0030110E <br/>Upper limit: FL660<br/>Lower limit: FL50<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 2.7113888889,53.4686111111,20116.8 2.9538888889,53.9263888889,20116.8 3.0200138889,54.2925722222,20116.8 3.0193416667,54.2940166667,20116.8 + + + + + relativeToGround + + + relativeToGround + 3.0193416667,54.2940166667,1524.0 0.599175,53.6369388889,1524.0 2.7113888889,53.4686111111,1524.0 2.9538888889,53.9263888889,1524.0 3.0200138889,54.2925722222,1524.0 3.0193416667,54.2940166667,1524.0 + + + + + relativeToGround + + + relativeToGround + 3.0193416667,54.2940166667,1524.0 0.599175,53.6369388889,1524.0 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524.0 + + + + + relativeToGround + + + relativeToGround + 0.599175,53.6369388889,1524.0 2.7113888889,53.4686111111,1524.0 2.7113888889,53.4686111111,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.7113888889,53.4686111111,1524.0 2.9538888889,53.9263888889,1524.0 2.9538888889,53.9263888889,20116.8 2.7113888889,53.4686111111,20116.8 2.7113888889,53.4686111111,1524.0 + + + + + relativeToGround + + + relativeToGround + 2.9538888889,53.9263888889,1524.0 3.0200138889,54.2925722222,1524.0 3.0200138889,54.2925722222,20116.8 2.9538888889,53.9263888889,20116.8 2.9538888889,53.9263888889,1524.0 + + + + + relativeToGround + + + relativeToGround + 3.0200138889,54.2925722222,1524.0 3.0193416667,54.2940166667,1524.0 3.0193416667,54.2940166667,20116.8 3.0200138889,54.2925722222,20116.8 3.0200138889,54.2925722222,1524.0 + + + + + + + EGD323F SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1631" txt_name="SOUTHERN COMPLEX"><tr><td>545744N 0005457W -<br/>544841N 0005456W -<br/>542402N 0005518W -<br/>544229N 0011251W -<br/>545210N 0010815W -<br/>545513N 0010343W -<br/>545744N 0005457W <br/>Upper limit: FL660<br/>Lower limit: FL150<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -0.9158333333,54.9623333333,20116.8 -1.0619444444,54.9202777778,20116.8 -1.1375,54.8694444444,20116.8 -1.2140305556,54.7081583333,20116.8 -0.9216388889,54.4006611111,20116.8 -0.9156,54.8112972222,20116.8 -0.9158333333,54.9623333333,20116.8 + + + + + relativeToGround + + + relativeToGround + -0.9158333333,54.9623333333,4572.0 -1.0619444444,54.9202777778,4572.0 -1.1375,54.8694444444,4572.0 -1.2140305556,54.7081583333,4572.0 -0.9216388889,54.4006611111,4572.0 -0.9156,54.8112972222,4572.0 -0.9158333333,54.9623333333,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9158333333,54.9623333333,4572.0 -1.0619444444,54.9202777778,4572.0 -1.0619444444,54.9202777778,20116.8 -0.9158333333,54.9623333333,20116.8 -0.9158333333,54.9623333333,4572.0 + + + + + relativeToGround + + + relativeToGround + -1.0619444444,54.9202777778,4572.0 -1.1375,54.8694444444,4572.0 -1.1375,54.8694444444,20116.8 -1.0619444444,54.9202777778,20116.8 -1.0619444444,54.9202777778,4572.0 + + + + + relativeToGround + + + relativeToGround + -1.1375,54.8694444444,4572.0 -1.2140305556,54.7081583333,4572.0 -1.2140305556,54.7081583333,20116.8 -1.1375,54.8694444444,20116.8 -1.1375,54.8694444444,4572.0 + + + + + relativeToGround + + + relativeToGround + -1.2140305556,54.7081583333,4572.0 -0.9216388889,54.4006611111,4572.0 -0.9216388889,54.4006611111,20116.8 -1.2140305556,54.7081583333,20116.8 -1.2140305556,54.7081583333,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9216388889,54.4006611111,4572.0 -0.9156,54.8112972222,4572.0 -0.9156,54.8112972222,20116.8 -0.9216388889,54.4006611111,20116.8 -0.9216388889,54.4006611111,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9156,54.8112972222,4572.0 -0.9158333333,54.9623333333,4572.0 -0.9158333333,54.9623333333,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572.0 + + + + + + + EGD323G SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1172" txt_name="SOUTHERN COMPLEX"><tr><td>544841N 0005456W -<br/>543102N 0003132W -<br/>542402N 0005518W -<br/>544841N 0005456W <br/>Upper limit: FL660<br/>Lower limit: FL150<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -0.9156,54.8112972222,20116.8 -0.9216388889,54.4006611111,20116.8 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 + + + + + relativeToGround + + + relativeToGround + -0.9156,54.8112972222,4572.0 -0.9216388889,54.4006611111,4572.0 -0.5256138889,54.5171138889,4572.0 -0.9156,54.8112972222,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9156,54.8112972222,4572.0 -0.9216388889,54.4006611111,4572.0 -0.9216388889,54.4006611111,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9216388889,54.4006611111,4572.0 -0.5256138889,54.5171138889,4572.0 -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.4006611111,20116.8 -0.9216388889,54.4006611111,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,4572.0 -0.9156,54.8112972222,4572.0 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572.0 + + + + + + + EGD323H SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2294" txt_name="SOUTHERN COMPLEX"><tr><td>543102N 0003132W -<br/>541451N 0001028W -<br/>540726N 0003547W -<br/>542402N 0005518W -<br/>543102N 0003132W <br/>Upper limit: FL660<br/>Lower limit: FL150<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.4006611111,20116.8 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 + + + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,4572.0 -0.9216388889,54.4006611111,4572.0 -0.5964777778,54.1240138889,4572.0 -0.1744611111,54.24745,4572.0 -0.5256138889,54.5171138889,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.5256138889,54.5171138889,4572.0 -0.9216388889,54.4006611111,4572.0 -0.9216388889,54.4006611111,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.9216388889,54.4006611111,4572.0 -0.5964777778,54.1240138889,4572.0 -0.5964777778,54.1240138889,20116.8 -0.9216388889,54.4006611111,20116.8 -0.9216388889,54.4006611111,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.5964777778,54.1240138889,4572.0 -0.1744611111,54.24745,4572.0 -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,4572.0 -0.5256138889,54.5171138889,4572.0 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572.0 + + + + + + + EGD323J SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2295" txt_name="SOUTHERN COMPLEX"><tr><td>541451N 0001028W -<br/>540644N 0000002W -<br/>535908N 0002606W -<br/>540726N 0003547W -<br/>541451N 0001028W <br/>Upper limit: FL660<br/>Lower limit: FL150<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.4349,53.9855666667,20116.8 -5.361111E-4,54.1121805556,20116.8 -0.1744611111,54.24745,20116.8 + + + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,4572.0 -0.5964777778,54.1240138889,4572.0 -0.4349,53.9855666667,4572.0 -5.361111E-4,54.1121805556,4572.0 -0.1744611111,54.24745,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.1744611111,54.24745,4572.0 -0.5964777778,54.1240138889,4572.0 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.5964777778,54.1240138889,4572.0 -0.4349,53.9855666667,4572.0 -0.4349,53.9855666667,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.4349,53.9855666667,4572.0 -5.361111E-4,54.1121805556,4572.0 -5.361111E-4,54.1121805556,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572.0 + + + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,4572.0 -0.1744611111,54.24745,4572.0 -0.1744611111,54.24745,20116.8 -5.361111E-4,54.1121805556,20116.8 -5.361111E-4,54.1121805556,4572.0 + + + + + + + EGD323K SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2296" txt_name="SOUTHERN COMPLEX"><tr><td>540644N 0000002W -<br/>533813N 0003557E -<br/>534331N 0000805W -<br/>535908N 0002606W -<br/>540644N 0000002W <br/>Upper limit: FL660<br/>Lower limit: FL150<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,20116.8 -0.4349,53.9855666667,20116.8 -0.1348055556,53.7253805556,20116.8 0.599175,53.6369388889,20116.8 -5.361111E-4,54.1121805556,20116.8 + + + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,4572.0 -0.4349,53.9855666667,4572.0 -0.1348055556,53.7253805556,4572.0 0.599175,53.6369388889,4572.0 -5.361111E-4,54.1121805556,4572.0 + + + + + relativeToGround + + + relativeToGround + -5.361111E-4,54.1121805556,4572.0 -0.4349,53.9855666667,4572.0 -0.4349,53.9855666667,20116.8 -5.361111E-4,54.1121805556,20116.8 -5.361111E-4,54.1121805556,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.4349,53.9855666667,4572.0 -0.1348055556,53.7253805556,4572.0 -0.1348055556,53.7253805556,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572.0 + + + + + relativeToGround + + + relativeToGround + -0.1348055556,53.7253805556,4572.0 0.599175,53.6369388889,4572.0 0.599175,53.6369388889,20116.8 -0.1348055556,53.7253805556,20116.8 -0.1348055556,53.7253805556,4572.0 + + + + + relativeToGround + + + relativeToGround + 0.599175,53.6369388889,4572.0 -5.361111E-4,54.1121805556,4572.0 -5.361111E-4,54.1121805556,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,4572.0 + + + + + + + EGD323L SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2297" txt_name="SOUTHERN COMPLEX"><tr><td>552430N 0004952E -<br/>550944N 0014759E -<br/>550143N 0011753E -<br/>551710N 0001428E -<br/>552430N 0004952E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 0.8311305556,55.4081972222,20116.8 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 + + + + + relativeToGround + + + relativeToGround + 0.8311305556,55.4081972222,3048.0 0.2412277778,55.2861722222,3048.0 1.298075,55.0285222222,3048.0 1.7996194444,55.1621805556,3048.0 0.8311305556,55.4081972222,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.8311305556,55.4081972222,3048.0 0.2412277778,55.2861722222,3048.0 0.2412277778,55.2861722222,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.2412277778,55.2861722222,3048.0 1.298075,55.0285222222,3048.0 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,3048.0 1.7996194444,55.1621805556,3048.0 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,3048.0 0.8311305556,55.4081972222,3048.0 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048.0 + + + + + + + EGD323M SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2298" txt_name="SOUTHERN COMPLEX"><tr><td>550944N 0014759E -<br/>545840N 0022938E -<br/>545059N 0020010E -<br/>550143N 0011753E -<br/>550944N 0014759E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.4938992222,54.9777948889,20116.8 1.7996194444,55.1621805556,20116.8 + + + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,3048.0 1.298075,55.0285222222,3048.0 2.0026916667,54.8496888889,3048.0 2.4938992222,54.9777948889,3048.0 1.7996194444,55.1621805556,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,3048.0 1.298075,55.0285222222,3048.0 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.298075,55.0285222222,3048.0 2.0026916667,54.8496888889,3048.0 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,3048.0 2.4938992222,54.9777948889,3048.0 2.4938992222,54.9777948889,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.4938992222,54.9777948889,3048.0 1.7996194444,55.1621805556,3048.0 1.7996194444,55.1621805556,20116.8 2.4938992222,54.9777948889,20116.8 2.4938992222,54.9777948889,3048.0 + + + + + + + EGD323N SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2299" txt_name="SOUTHERN COMPLEX"><tr><td>545840N 0022938E -<br/>544951N 0023752E -<br/>544532N 0022109E -<br/>545059N 0020010E -<br/>545840N 0022938E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 2.4938992222,54.9777948889,20116.8 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875,20116.8 2.6309753889,54.8308915833,20116.8 2.4938992222,54.9777948889,20116.8 + + + + + relativeToGround + + + relativeToGround + 2.4938992222,54.9777948889,3048.0 2.0026916667,54.8496888889,3048.0 2.3526361111,54.75875,3048.0 2.6309753889,54.8308915833,3048.0 2.4938992222,54.9777948889,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.4938992222,54.9777948889,3048.0 2.0026916667,54.8496888889,3048.0 2.0026916667,54.8496888889,20116.8 2.4938992222,54.9777948889,20116.8 2.4938992222,54.9777948889,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.0026916667,54.8496888889,3048.0 2.3526361111,54.75875,3048.0 2.3526361111,54.75875,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,3048.0 2.6309753889,54.8308915833,3048.0 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875,20116.8 2.3526361111,54.75875,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.6309753889,54.8308915833,3048.0 2.4938992222,54.9777948889,3048.0 2.4938992222,54.9777948889,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048.0 + + + + + + + EGD323P SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2300" txt_name="SOUTHERN COMPLEX"><tr><td>544951N 0023752E -<br/>543143N 0025434E -<br/>543948N 0024252E -<br/>544532N 0022109E -<br/>544951N 0023752E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875,20116.8 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.6309753889,54.8308915833,20116.8 + + + + + relativeToGround + + + relativeToGround + 2.6309753889,54.8308915833,3048.0 2.3526361111,54.75875,3048.0 2.7144361111,54.6632333333,3048.0 2.9095444444,54.5285361111,3048.0 2.6309753889,54.8308915833,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.6309753889,54.8308915833,3048.0 2.3526361111,54.75875,3048.0 2.3526361111,54.75875,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.3526361111,54.75875,3048.0 2.7144361111,54.6632333333,3048.0 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875,20116.8 2.3526361111,54.75875,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.7144361111,54.6632333333,3048.0 2.9095444444,54.5285361111,3048.0 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.9095444444,54.5285361111,3048.0 2.6309753889,54.8308915833,3048.0 2.6309753889,54.8308915833,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,3048.0 + + + + + + + EGD323Q SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2301" txt_name="SOUTHERN COMPLEX"><tr><td>553347N 0013625E -<br/>553150N 0015622E -<br/>551616N 0021300E -<br/>550944N 0014759E -<br/>552430N 0004952E -<br/>553347N 0013625E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 1.6068611111,55.5631527778,20116.8 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 1.9394305556,55.5305138889,20116.8 1.6068611111,55.5631527778,20116.8 + + + + + relativeToGround + + + relativeToGround + 1.6068611111,55.5631527778,3048.0 0.8311305556,55.4081972222,3048.0 1.7996194444,55.1621805556,3048.0 2.2167416667,55.2711027778,3048.0 1.9394305556,55.5305138889,3048.0 1.6068611111,55.5631527778,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.6068611111,55.5631527778,3048.0 0.8311305556,55.4081972222,3048.0 0.8311305556,55.4081972222,20116.8 1.6068611111,55.5631527778,20116.8 1.6068611111,55.5631527778,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.8311305556,55.4081972222,3048.0 1.7996194444,55.1621805556,3048.0 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,3048.0 2.2167416667,55.2711027778,3048.0 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.2167416667,55.2711027778,3048.0 1.9394305556,55.5305138889,3048.0 1.9394305556,55.5305138889,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.9394305556,55.5305138889,3048.0 1.6068611111,55.5631527778,3048.0 1.6068611111,55.5631527778,20116.8 1.9394305556,55.5305138889,20116.8 1.9394305556,55.5305138889,3048.0 + + + + + + + EGD323R SOUTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="2302" txt_name="SOUTHERN COMPLEX"><tr><td>551616N 0021300E -<br/>545840N 0022938E -<br/>550944N 0014759E -<br/>551616N 0021300E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 2.4938992222,54.9777948889,20116.8 2.2167416667,55.2711027778,20116.8 + + + + + relativeToGround + + + relativeToGround + 2.2167416667,55.2711027778,3048.0 1.7996194444,55.1621805556,3048.0 2.4938992222,54.9777948889,3048.0 2.2167416667,55.2711027778,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.2167416667,55.2711027778,3048.0 1.7996194444,55.1621805556,3048.0 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.7996194444,55.1621805556,3048.0 2.4938992222,54.9777948889,3048.0 2.4938992222,54.9777948889,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048.0 + + + + + relativeToGround + + + relativeToGround + 2.4938992222,54.9777948889,3048.0 2.2167416667,55.2711027778,3048.0 2.2167416667,55.2711027778,20116.8 2.4938992222,54.9777948889,20116.8 2.4938992222,54.9777948889,3048.0 + + + + + + + EGD324A WADDINGTON LOW + <table border="1" cellpadding="1" cellspacing="0" row_id="13543" txt_name="WADDINGTON LOW"><tr><td>A circle, 5 NM radius, centred at 530958N 0003126W <br/>Upper limit: FL105<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres.<br/><br/>Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Waddington ATC, Tel: 01522-727451/727452.<br/><br/>Remarks: High energy manoeuvres related to display flying training only.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5238888889,53.2493170173,3200.4 -0.5329620222,53.2491385233,3200.4 -0.5419960775,53.2486038102,3200.4 -0.5509521479,53.2477151807,3200.4 -0.5597916681,53.2464764618,3200.4 -0.5684765836,53.2448929879,3200.4 -0.5769695164,53.2429715769,3200.4 -0.5852339289,53.2407205011,3200.4 -0.5932342833,53.2381494508,3200.4 -0.6009361957,53.2352694915,3200.4 -0.6083065862,53.2320930161,3200.4 -0.6153138218,53.2286336905,3200.4 -0.6219278531,53.2249063941,3200.4 -0.6281203442,53.2209271548,3200.4 -0.6338647934,53.2167130794,3200.4 -0.6391366472,53.2122822792,3200.4 -0.6439134041,53.2076537911,3200.4 -0.6481747101,53.202847495,3200.4 -0.6519024438,53.197884028,3200.4 -0.6550807917,53.1927846947,3200.4 -0.6576963139,53.1875713753,3200.4 -0.6597379981,53.182266431,3200.4 -0.6611973038,53.1768926078,3200.4 -0.6620681955,53.1714729387,3200.4 -0.6623471645,53.1660306441,3200.4 -0.6620332407,53.1605890328,3200.4 -0.6611279923,53.1551714022,3200.4 -0.6596355158,53.1498009378,3200.4 -0.6575624144,53.144500615,3200.4 -0.6549177659,53.1392931008,3200.4 -0.651713081,53.134200657,3200.4 -0.6479622505,53.129245046,3200.4 -0.6436814828,53.124447438,3200.4 -0.6388892324,53.1198283214,3200.4 -0.6336061185,53.1154074157,3200.4 -0.6278548351,53.1112035887,3200.4 -0.6216600529,53.1072347761,3200.4 -0.6150483124,53.1035179065,3200.4 -0.6080479107,53.1000688292,3200.4 -0.6006887801,53.0969022484,3200.4 -0.5930023609,53.0940316606,3200.4 -0.5850214681,53.0914692984,3200.4 -0.5767801523,53.0892260788,3200.4 -0.5683135565,53.0873115574,3200.4 -0.5596577674,53.0857338887,3200.4 -0.5508496647,53.0844997914,3200.4 -0.5419267654,53.0836145207,3200.4 -0.5329270671,53.0830818461,3200.4 -0.5238888889,53.0829040355,3200.4 -0.5148507107,53.0830818461,3200.4 -0.5058510124,53.0836145207,3200.4 -0.4969281131,53.0844997914,3200.4 -0.4881200103,53.0857338887,3200.4 -0.4794642213,53.0873115574,3200.4 -0.4709976254,53.0892260788,3200.4 -0.4627563097,53.0914692984,3200.4 -0.4547754169,53.0940316606,3200.4 -0.4470889977,53.0969022484,3200.4 -0.4397298671,53.1000688292,3200.4 -0.4327294654,53.1035179065,3200.4 -0.4261177249,53.1072347761,3200.4 -0.4199229426,53.1112035887,3200.4 -0.4141716593,53.1154074157,3200.4 -0.4088885453,53.1198283214,3200.4 -0.4040962949,53.124447438,3200.4 -0.3998155273,53.129245046,3200.4 -0.3960646967,53.134200657,3200.4 -0.3928600119,53.1392931008,3200.4 -0.3902153634,53.144500615,3200.4 -0.3881422619,53.1498009378,3200.4 -0.3866497854,53.1551714022,3200.4 -0.3857445371,53.1605890328,3200.4 -0.3854306133,53.1660306441,3200.4 -0.3857095823,53.1714729387,3200.4 -0.386580474,53.1768926078,3200.4 -0.3880397797,53.182266431,3200.4 -0.3900814638,53.1875713753,3200.4 -0.392696986,53.1927846947,3200.4 -0.395875334,53.197884028,3200.4 -0.3996030676,53.202847495,3200.4 -0.4038643737,53.2076537911,3200.4 -0.4086411306,53.2122822792,3200.4 -0.4139129844,53.2167130794,3200.4 -0.4196574336,53.2209271548,3200.4 -0.4258499247,53.2249063941,3200.4 -0.432463956,53.2286336905,3200.4 -0.4394711916,53.2320930161,3200.4 -0.4468415821,53.2352694915,3200.4 -0.4545434945,53.2381494508,3200.4 -0.4625438488,53.2407205011,3200.4 -0.4708082614,53.2429715769,3200.4 -0.4793011942,53.2448929879,3200.4 -0.4879861096,53.2464764618,3200.4 -0.4968256299,53.2477151807,3200.4 -0.5057817003,53.2486038102,3200.4 -0.5148157555,53.2491385233,3200.4 -0.5238888889,53.2493170173,3200.4 + + + + + + EGD324B WADDINGTON MEDIUM + <table border="1" cellpadding="1" cellspacing="0" row_id="13545" txt_name="WADDINGTON MEDIUM"><tr><td>531343N 0004324W -<br/>530818N 0001452W -<br/>525556N 0002123W -<br/>530120N 0004950W -<br/>531343N 0004324W <br/>Upper limit: FL195<br/>Lower limit: FL105<br/>Class: </td><td>Activity: Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.<br/><br/>Contact: Waddington ATC, Tel: 01522-727451/727452.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -0.7233333333,53.2286111111,5943.6 -0.8306333333,53.0220944444,5943.6 -0.3564722222,52.9321694444,5943.6 -0.247825,53.1383611111,5943.6 -0.7233333333,53.2286111111,5943.6 + + + + + relativeToGround + + + relativeToGround + -0.7233333333,53.2286111111,3200.4 -0.8306333333,53.0220944444,3200.4 -0.3564722222,52.9321694444,3200.4 -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 + + + + + relativeToGround + + + relativeToGround + -0.7233333333,53.2286111111,3200.4 -0.8306333333,53.0220944444,3200.4 -0.8306333333,53.0220944444,5943.6 -0.7233333333,53.2286111111,5943.6 -0.7233333333,53.2286111111,3200.4 + + + + + relativeToGround + + + relativeToGround + -0.8306333333,53.0220944444,3200.4 -0.3564722222,52.9321694444,3200.4 -0.3564722222,52.9321694444,5943.6 -0.8306333333,53.0220944444,5943.6 -0.8306333333,53.0220944444,3200.4 + + + + + relativeToGround + + + relativeToGround + -0.3564722222,52.9321694444,3200.4 -0.247825,53.1383611111,3200.4 -0.247825,53.1383611111,5943.6 -0.3564722222,52.9321694444,5943.6 -0.3564722222,52.9321694444,3200.4 + + + + + relativeToGround + + + relativeToGround + -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 -0.7233333333,53.2286111111,5943.6 -0.247825,53.1383611111,5943.6 -0.247825,53.1383611111,3200.4 + + + + + + + EGD401 BALLYKINLER + <table border="1" cellpadding="1" cellspacing="0" row_id="1011" txt_name="BALLYKINLER"><tr><td>541334N 0054612W -<br/>541256N 0054734W -<br/>541316N 0055038W -<br/>541440N 0054940W - then along the river to<br/>541526N 0055010W -<br/>541525N 0054718W -<br/>541334N 0054612W <br/>Upper limit: 3200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 02844-610392.<br/><br/>Remarks: SI 1940/756.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.77,54.2261111111,975.36 -5.7883333333,54.2569444444,975.36 -5.8361111111,54.2572222222,975.36 -5.8353861111,54.2552055556,975.36 -5.8287416667,54.2502138889,975.36 -5.8250583333,54.2466888889,975.36 -5.8255055556,54.2453583333,975.36 -5.8277777778,54.2444444444,975.36 -5.8438888889,54.2211111111,975.36 -5.7927777778,54.2155555556,975.36 -5.77,54.2261111111,975.36 + + + + + + EGD402A LUCE BAY (N) + <table border="1" cellpadding="1" cellspacing="0" row_id="1012" txt_name="LUCE BAY (N)"><tr><td>550332N 0050509W -<br/>545600N 0045800W -<br/>545600N 0044744W -<br/>544650N 0043837W -<br/>545008N 0044939W -<br/>545100N 0044946W -<br/>545217N 0045134W -<br/>545208N 0045404W -<br/>544953N 0045653W -<br/>544541N 0045627W -<br/>544215N 0045339W -<br/>544007N 0045032W -<br/>543915N 0044653W -<br/>543815N 0045352W -<br/>545812N 0051210W -<br/>550218N 0050909W -<br/>550332N 0050509W <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 3000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01776-888930.<br/><br/>Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0858333333,55.0588888889,7010.400000000001 -5.1525,55.0383333333,7010.400000000001 -5.2027777778,54.97,7010.400000000001 -4.8977777778,54.6375,7010.400000000001 -4.7813888889,54.6541666667,7010.400000000001 -4.8422222222,54.6686111111,7010.400000000001 -4.8941666667,54.7041666667,7010.400000000001 -4.9408333333,54.7613888889,7010.400000000001 -4.9480555556,54.8313888889,7010.400000000001 -4.9011111111,54.8688888889,7010.400000000001 -4.8594444444,54.8713888889,7010.400000000001 -4.8294444444,54.85,7010.400000000001 -4.8275,54.8355555556,7010.400000000001 -4.6436111111,54.7805555556,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + + + EGD402B LUCE BAY (N) + <table border="1" cellpadding="1" cellspacing="0" row_id="1013" txt_name="LUCE BAY (N)"><tr><td>550332N 0050509W -<br/>550254N 0045410W -<br/>545600N 0044744W -<br/>545600N 0045800W -<br/>550332N 0050509W <br/>Upper limit: 23000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 3000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01776-888930.<br/><br/>Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0858333333,55.0588888889,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9027777778,55.0483333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + + + EGD402C LUCE BAY (N) + <table border="1" cellpadding="1" cellspacing="0" row_id="1014" txt_name="LUCE BAY (N)"><tr><td>A circle, 3000 FT radius, centred at 545659N 0045752W <br/>Upper limit: 4000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01776-888930.<br/><br/>Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9644444444,54.9579361819,1219.2 -4.9673177437,54.9577680078,1219.2 -4.9700733403,54.9572703748,1219.2 -4.9725983613,54.9564636675,1219.2 -4.9747893947,54.9553809299,1219.2 -4.9765567285,54.9540665095,1219.2 -4.9778280257,54.9525742383,1219.2 -4.9785512828,54.9509652263,1219.2 -4.9786969516,54.9493053564,1219.2 -4.9782591389,54.9476625859,1219.2 -4.9772558366,54.9461041639,1219.2 -4.9757281738,54.9446938793,1219.2 -4.9737387244,54.9434894509,1219.2 -4.9713689403,54.942540168,1219.2 -4.968715816,54.9418848754,1219.2 -4.9658879218,54.9415503861,1219.2 -4.963000967,54.9415503861,1219.2 -4.9601730729,54.9418848754,1219.2 -4.9575199486,54.942540168,1219.2 -4.9551501645,54.9434894509,1219.2 -4.9531607151,54.9446938793,1219.2 -4.9516330523,54.9461041639,1219.2 -4.95062975,54.9476625859,1219.2 -4.9501919373,54.9493053564,1219.2 -4.9503376061,54.9509652263,1219.2 -4.9510608631,54.9525742383,1219.2 -4.9523321604,54.9540665095,1219.2 -4.9540994942,54.9553809299,1219.2 -4.9562905276,54.9564636675,1219.2 -4.9588155486,54.9572703748,1219.2 -4.9615711452,54.9577680078,1219.2 -4.9644444444,54.9579361819,1219.2 + + + + + + EGD403A LUCE BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1016" txt_name="LUCE BAY"><tr><td>545141N 0045438W -<br/>545139N 0045041W -<br/>545100N 0044946W -<br/>544850N 0045646W -<br/>544953N 0045653W -<br/>545141N 0045438W <br/>Upper limit: 3000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01776-888930.<br/><br/>Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9105555556,54.8613888889,914.4000000000001 -4.9480555556,54.8313888889,914.4000000000001 -4.9461111111,54.8138888889,914.4000000000001 -4.8294444444,54.85,914.4000000000001 -4.8447222222,54.8608333333,914.4000000000001 -4.9105555556,54.8613888889,914.4000000000001 + + + + + + EGD403B LUCE BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1015" txt_name="LUCE BAY"><tr><td>545208N 0045404W -<br/>545217N 0045134W -<br/>545100N 0044946W -<br/>545008N 0044939W -<br/>544650N 0043837W -<br/>544304N 0043500W -<br/>544050N 0043543W -<br/>543915N 0044653W -<br/>544007N 0045032W -<br/>544215N 0045339W -<br/>544541N 0045627W -<br/>544953N 0045653W -<br/>545208N 0045404W <br/>Upper limit: 35000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01776-888930.<br/><br/>Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9011111111,54.8688888889,10668.0 -4.9480555556,54.8313888889,10668.0 -4.9408333333,54.7613888889,10668.0 -4.8941666667,54.7041666667,10668.0 -4.8422222222,54.6686111111,10668.0 -4.7813888889,54.6541666667,10668.0 -4.5952777778,54.6805555556,10668.0 -4.5833333333,54.7177777778,10668.0 -4.6436111111,54.7805555556,10668.0 -4.8275,54.8355555556,10668.0 -4.8294444444,54.85,10668.0 -4.8594444444,54.8713888889,10668.0 -4.9011111111,54.8688888889,10668.0 + + + + + + EGD405 KIRKCUDBRIGHT + <table border="1" cellpadding="1" cellspacing="0" row_id="1622" txt_name="KIRKCUDBRIGHT"><tr><td>544647N 0040349W -<br/>544744N 0040214W -<br/>544828N 0040040W -<br/>544818N 0035705W -<br/>544710N 0035630W -<br/>543800N 0034806W -<br/>543302N 0035720W -<br/>543315N 0041341W -<br/>543537N 0041514W -<br/>544647N 0040349W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 15,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 50,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information / Booking: Kirkcudbright Range TSO, Tel: 01412-248500. DTSO 01412-248501.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0636111111,54.7797222222,15240.0 -4.2538888889,54.5936111111,15240.0 -4.2280555556,54.5541666667,15240.0 -3.9555555556,54.5505555556,15240.0 -3.8016666667,54.6333333333,15240.0 -3.9416666667,54.7861111111,15240.0 -3.9513888889,54.805,15240.0 -4.0111111111,54.8077777778,15240.0 -4.0372222222,54.7955555556,15240.0 -4.0636111111,54.7797222222,15240.0 + + + + + + EGD406A ESKMEALS + <table border="1" cellpadding="1" cellspacing="0" row_id="1017" txt_name="ESKMEALS"><tr><td>542057N 0032747W thence clockwise by the arc of a circle radius 2 NM centred on 541900N 0032705W to<br/>541701N 0032723W -<br/>540634N 0033920W thence clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to<br/>542357N 0034917W -<br/>542846N 0033842W -<br/>542057N 0032747W <br/>Upper limit: 80000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 50,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.<br/><br/>Remarks: Aircraft following the west coast may proceed through the Danger Area at a height not below 2000 FT but it is essential that they remain east of the main railway line paralleling the coast while within the Danger Area. SI 1982/1180.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4630555556,54.3491666667,24384.0 -3.645,54.4794444444,24384.0 -3.8213888889,54.3991666667,24384.0 -3.8264346983,54.3902456908,24384.0 -3.8308435947,54.381210064,24384.0 -3.8346650828,54.3720838636,24384.0 -3.8378941188,54.3628800713,24384.0 -3.8405265112,54.353611771,24384.0 -3.8425589244,54.3442921289,24384.0 -3.8439888809,54.3349343758,24384.0 -3.8448147631,54.3255517871,24384.0 -3.8450358126,54.3161576648,24384.0 -3.8446521295,54.306765318,24384.0 -3.8436646694,54.2973880444,24384.0 -3.8420752404,54.2880391114,24384.0 -3.8398864974,54.2787317371,24384.0 -3.8371019368,54.2694790723,24384.0 -3.8337258888,54.2602941817,24384.0 -3.8297635095,54.2511900257,24384.0 -3.8252207712,54.2421794422,24384.0 -3.8201044522,54.233275129,24384.0 -3.8144221249,54.2244896262,24384.0 -3.8081821439,54.2158352985,24384.0 -3.801393632,54.2073243185,24384.0 -3.7940664656,54.1989686499,24384.0 -3.7862112598,54.1907800309,24384.0 -3.7778393517,54.1827699581,24384.0 -3.7689627833,54.1749496712,24384.0 -3.7595942835,54.1673301372,24384.0 -3.7497472491,54.1599220357,24384.0 -3.7394357252,54.1527357444,24384.0 -3.7286743851,54.1457813251,24384.0 -3.7174785086,54.1390685101,24384.0 -3.7058639609,54.1326066888,24384.0 -3.6938471693,54.1264048954,24384.0 -3.6814451008,54.1204717968,24384.0 -3.6686752382,54.1148156806,24384.0 -3.6555555556,54.1094444444,24384.0 -3.4563888889,54.2836111111,24384.0 -3.4506623994,54.2834617223,24384.0 -3.4449398451,54.2836739162,24384.0 -3.4392829629,54.2842226211,24384.0 -3.433749363,54.2851022495,24384.0 -3.428395409,54.2863038428,24384.0 -3.4232756474,54.2878151632,24384.0 -3.4184422552,54.2896208163,24384.0 -3.4139445105,54.291702408,24384.0 -3.4098282922,54.2940387298,24384.0 -3.4061356127,54.2966059743,24384.0 -3.4029041892,54.2993779763,24384.0 -3.4001670583,54.3023264784,24384.0 -3.397952236,54.3054214177,24384.0 -3.396282429,54.3086312313,24384.0 -3.3951747988,54.3119231776,24384.0 -3.3946407821,54.3152636691,24384.0 -3.3946859681,54.318618615,24384.0 -3.3953100364,54.3219537687,24384.0 -3.3965067544,54.3252350775,24384.0 -3.3982640352,54.3284290303,24384.0 -3.4005640558,54.3315030008,24384.0 -3.4033834341,54.334425581,24384.0 -3.4066934642,54.3371669033,24384.0 -3.410460406,54.339698947,24384.0 -3.4146458278,54.3419958252,24384.0 -3.4192069976,54.3440340516,24384.0 -3.4240973199,54.3457927812,24384.0 -3.4292668128,54.3472540251,24384.0 -3.4346626206,54.3484028352,24384.0 -3.4402295569,54.3492274587,24384.0 -3.4459106726,54.3497194586,24384.0 -3.4516478419,54.3498738009,24384.0 -3.4573823616,54.3496889063,24384.0 -3.4630555556,54.3491666667,24384.0 + + + + + + EGD406B ESKMEALS + <table border="1" cellpadding="1" cellspacing="0" row_id="1018" txt_name="ESKMEALS"><tr><td>541913N 0035042W thence anti-clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to<br/>541049N 0034630W -<br/>540804N 0035336W thence clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to<br/>541916N 0035914W -<br/>541913N 0035042W <br/>Upper limit: 80000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 50,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.845,54.3202777778,24384.0 -3.9872222222,54.3211111111,24384.0 -3.9871594946,54.3107175685,24384.0 -3.9864927438,54.3003308501,24384.0 -3.985272219,54.2899613462,24384.0 -3.9834995252,54.2796191549,24384.0 -3.9811768014,54.26931434,24384.0 -3.9783067165,54.2590569217,24384.0 -3.9748924651,54.2488568664,24384.0 -3.9709377632,54.2387240779,24384.0 -3.9664468432,54.2286683871,24384.0 -3.9614244476,54.2186995434,24384.0 -3.955875824,54.2088272049,24384.0 -3.9498067176,54.1990609292,24384.0 -3.9432233654,54.189410165,24384.0 -3.936132488,54.1798842425,24384.0 -3.9285412827,54.1704923649,24384.0 -3.9204574148,54.1612435998,24384.0 -3.9118890095,54.1521468707,24384.0 -3.902844643,54.1432109488,24384.0 -3.8933333333,54.1344444444,24384.0 -3.775,54.1802777778,24384.0 -3.7834591208,54.1880869067,24384.0 -3.7913702592,54.1960923758,24384.0 -3.7987730162,54.2042637884,24384.0 -3.8056570042,54.2125900125,24384.0 -3.8120125251,54.2210596989,24384.0 -3.8178305841,54.2296612956,24384.0 -3.8231029043,54.2383830637,24384.0 -3.827821939,54.2472130929,24384.0 -3.831980884,54.2561393174,24384.0 -3.8355736883,54.2651495321,24384.0 -3.8385950649,54.2742314093,24384.0 -3.8410404991,54.2833725151,24384.0 -3.8429062576,54.2925603262,24384.0 -3.8441893949,54.3017822471,24384.0 -3.8448877597,54.3110256271,24384.0 -3.845,54.3202777778,24384.0 + + + + + + EGD406C ESKMEALS + <table border="1" cellpadding="1" cellspacing="0" row_id="1019" txt_name="ESKMEALS"><tr><td>541916N 0035914W thence anti-clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to<br/>540804N 0035336W -<br/>541027N 0040844W thence clockwise by the arc of a circle radius 27 NM centred on 541900N 0032505W to<br/>541413N 0041025W -<br/>541916N 0035914W <br/>Upper limit: 50000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9872222222,54.3211111111,15240.0 -4.1736111111,54.2369444444,15240.0 -4.1699727629,54.2263311513,15240.0 -4.1659452033,54.2157666889,15240.0 -4.1614866885,54.2052619799,15240.0 -4.1566001131,54.1948230752,15240.0 -4.1512886114,54.1844559832,15240.0 -4.1455555556,54.1741666667,15240.0 -3.8933333333,54.1344444444,15240.0 -3.9028029361,54.1432260183,15240.0 -3.9118465154,54.1521611714,15240.0 -3.920414174,54.1612571176,15240.0 -3.9284973363,54.1705050866,15240.0 -3.936087878,54.1798961556,15240.0 -3.9431781344,54.1894212578,15240.0 -3.949760909,54.1990711908,15240.0 -3.9558294816,54.208836625,15240.0 -3.961377616,54.2187081128,15240.0 -3.9663995673,54.2286760972,15240.0 -3.9708900887,54.238730921,15240.0 -3.9748444377,54.2488628357,15240.0 -3.9782583827,54.2590620111,15240.0 -3.981128208,54.2693185444,15240.0 -3.9834507192,54.27962247,15240.0 -3.9852232477,54.2899637685,15240.0 -3.9864436549,54.300332377,15240.0 -3.9871103357,54.3107181984,15240.0 -3.9872222222,54.3211111111,15240.0 + + + + + + EGD407 WARCOP + <table border="1" cellpadding="1" cellspacing="0" row_id="1623" txt_name="WARCOP"><tr><td>543812N 0022047W -<br/>543856N 0021445W -<br/>543753N 0021402W -<br/>543432N 0021545W -<br/>543156N 0022043W -<br/>543202N 0022209W -<br/>543343N 0022536W -<br/>543526N 0022419W -<br/>543812N 0022047W <br/>Upper limit: 13500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 10,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 13,500 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01768-343224.<br/><br/>Remarks: SI 1981/623.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3463888889,54.6366666667,4114.8 -2.4052777778,54.5905555556,4114.8 -2.4266666667,54.5619444444,4114.8 -2.3691666667,54.5338888889,4114.8 -2.3452777778,54.5322222222,4114.8 -2.2625,54.5755555556,4114.8 -2.2338888889,54.6313888889,4114.8 -2.2458333333,54.6488888889,4114.8 -2.3463888889,54.6366666667,4114.8 + + + + + + EGD408 FELDOM + <table border="1" cellpadding="1" cellspacing="0" row_id="1624" txt_name="FELDOM"><tr><td>542826N 0015159W -<br/>542750N 0014921W -<br/>542656N 0014654W -<br/>542513N 0014819W -<br/>542447N 0015004W -<br/>542505N 0015159W -<br/>542720N 0015350W -<br/>542826N 0015159W <br/>Upper limit: 5600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 3000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 5600 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/ BVLOS) (less than 150 KTS).<br/><br/>Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.<br/><br/>Remarks: SI 1976/566.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8663888889,54.4738888889,1706.88 -1.8972222222,54.4555555556,1706.88 -1.8663888889,54.4180555556,1706.88 -1.8344444444,54.4130555556,1706.88 -1.8052777778,54.4202777778,1706.88 -1.7816666667,54.4488888889,1706.88 -1.8225,54.4638888889,1706.88 -1.8663888889,54.4738888889,1706.88 + + + + + + EGD410 STRENSALL + <table border="1" cellpadding="1" cellspacing="0" row_id="1027" txt_name="STRENSALL"><tr><td>A circle, 3000 FT radius, centred at 540136N 0010101W <br/>Upper limit: 1000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01904-442966.<br/><br/>Remarks: SI 1972/246.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0169444444,54.0348818885,304.8 -1.0197537238,54.0347136897,304.8 -1.0224479252,54.0342159834,304.8 -1.0249166926,54.033409157,304.8 -1.027058919,54.0323262586,304.8 -1.0287868913,54.0310116417,304.8 -1.0300298828,54.0295191457,304.8 -1.0307370464,54.0279098892,304.8 -1.0308794896,54.0262497647,304.8 -1.0304514472,54.0246067401,304.8 -1.0294705074,54.023048075,304.8 -1.0279768809,54.0216375685,304.8 -1.0260317464,54.0204329494,304.8 -1.0237147413,54.0194835154,304.8 -1.0211207007,54.018828118,304.8 -1.0183557787,54.018493575,304.8 -1.0155331101,54.018493575,304.8 -1.0127681882,54.018828118,304.8 -1.0101741476,54.0194835154,304.8 -1.0078571425,54.0204329494,304.8 -1.005912008,54.0216375685,304.8 -1.0044183814,54.023048075,304.8 -1.0034374417,54.0246067401,304.8 -1.0030093993,54.0262497647,304.8 -1.0031518424,54.0279098892,304.8 -1.0038590061,54.0295191457,304.8 -1.0051019976,54.0310116417,304.8 -1.0068299699,54.0323262586,304.8 -1.0089721963,54.033409157,304.8 -1.0114409637,54.0342159834,304.8 -1.0141351651,54.0347136897,304.8 -1.0169444444,54.0348818885,304.8 + + + + + + EGD412 STAXTON + <table border="1" cellpadding="1" cellspacing="0" row_id="1028" txt_name="STAXTON"><tr><td>545800N 0002300W -<br/>552500N 0010000E -<br/>550400N 0012100E -<br/>544545N 0005455E following the line of latitude to -<br/>544545N 0000917W -<br/>545800N 0002300W <br/>Upper limit: 10000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3833333333,54.9666666667,3048.0 -0.1547222222,54.7625,3048.0 -0.0018650794,54.7625,3048.0 0.1509920635,54.7625,3048.0 0.3038492063,54.7625,3048.0 0.4567063492,54.7625,3048.0 0.6095634921,54.7625,3048.0 0.7624206349,54.7625,3048.0 0.9152777778,54.7625,3048.0 1.35,55.0666666667,3048.0 1.0,55.4166666667,3048.0 -0.3833333333,54.9666666667,3048.0 + + + + + + EGD442 BELLERBY + <table border="1" cellpadding="1" cellspacing="0" row_id="1029" txt_name="BELLERBY"><tr><td>A circle, 2300 M radius, centred at 542039N 0015125W <br/>Upper limit: 3000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) (less than 150 KTS).<br/><br/>Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.<br/><br/>Remarks: SI 1984/1770.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8569444444,54.3648293837,914.4000000000001 -1.8615629685,54.3646525232,914.4000000000001 -1.8661023509,54.3641249725,914.4000000000001 -1.8704848124,54.3632557713,914.4000000000001 -1.874635274,54.3620598126,914.4000000000001 -1.8784826481,54.3605575869,914.4000000000001 -1.8819610599,54.3587748295,914.4000000000001 -1.8850109775,54.3567420778,914.4000000000001 -1.8875802316,54.3544941467,914.4000000000001 -1.8896249068,54.3520695308,914.4000000000001 -1.8911100904,54.3495097429,914.4000000000001 -1.8920104643,54.3468586027,914.4000000000001 -1.8923107321,54.344161485,914.4000000000001 -1.8920058734,54.3414645427,914.4000000000001 -1.8911012215,54.3388139166,914.4000000000001 -1.8896123644,54.3362549466,914.4000000000001 -1.8875648703,54.3338313964,914.4000000000001 -1.8849938442,54.3315847065,914.4000000000001 -1.8819433222,54.3295532866,914.4000000000001 -1.8784655147,54.3277718611,914.4000000000001 -1.8746199127,54.3262708765,914.4000000000001 -1.8704722699,54.3250759836,914.4000000000001 -1.8660934821,54.3242076002,914.4000000000001 -1.8615583776,54.3236805636,914.4000000000001 -1.8569444444,54.3235038785,914.4000000000001 -1.8523305113,54.3236805636,914.4000000000001 -1.8477954068,54.3242076002,914.4000000000001 -1.8434166189,54.3250759836,914.4000000000001 -1.8392689762,54.3262708765,914.4000000000001 -1.8354233741,54.3277718611,914.4000000000001 -1.8319455667,54.3295532866,914.4000000000001 -1.8288950447,54.3315847065,914.4000000000001 -1.8263240186,54.3338313964,914.4000000000001 -1.8242765245,54.3362549466,914.4000000000001 -1.8227876674,54.3388139166,914.4000000000001 -1.8218830155,54.3414645427,914.4000000000001 -1.8215781568,54.344161485,914.4000000000001 -1.8218784246,54.3468586027,914.4000000000001 -1.8227787985,54.3495097429,914.4000000000001 -1.8242639821,54.3520695308,914.4000000000001 -1.8263086573,54.3544941467,914.4000000000001 -1.8288779114,54.3567420778,914.4000000000001 -1.831927829,54.3587748295,914.4000000000001 -1.8354062408,54.3605575869,914.4000000000001 -1.8392536149,54.3620598126,914.4000000000001 -1.8434040765,54.3632557713,914.4000000000001 -1.847786538,54.3641249725,914.4000000000001 -1.8523259204,54.3646525232,914.4000000000001 -1.8569444444,54.3648293837,914.4000000000001 + + + + + + EGD505 MAGILLIGAN + <table border="1" cellpadding="1" cellspacing="0" row_id="1030" txt_name="MAGILLIGAN"><tr><td>551117N 0065827W -<br/>551307N 0065423W -<br/>551253N 0065133W -<br/>551107N 0064948W -<br/>551010N 0065158W -<br/>551008N 0065633W -<br/>551117N 0065827W <br/>Upper limit: 6500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 2000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 6500 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 02877-720029.<br/><br/>Remarks: SI 1940/949.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.9741666667,55.1880555556,1981.2 -6.9425,55.1688888889,1981.2 -6.8661111111,55.1694444444,1981.2 -6.83,55.1852777778,1981.2 -6.8591666667,55.2147222222,1981.2 -6.9063888889,55.2186111111,1981.2 -6.9741666667,55.1880555556,1981.2 + + + + + + EGD508 RIDSDALE + <table border="1" cellpadding="1" cellspacing="0" row_id="1648" txt_name="RIDSDALE"><tr><td>A circle, 1200 M radius, centred at 550845N 0021007W <br/>Upper limit: 4100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUACS: Newcastle APP on 124.380 MHz. SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information: Range Reception, Tel: 01434-220952.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1686111111,55.1566124562,1249.68 -2.1719724508,55.1564391851,1249.68 -2.1752256692,55.1559249452,1249.68 -2.178266131,55.1550862772,1249.68 -2.1809960593,55.153950156,1249.68 -2.1833276853,55.1525531206,1249.68 -2.1851860725,55.1509400976,1249.68 -2.186511525,55.1491629534,1249.68 -2.1872615013,55.1472788247,1249.68 -2.1874119744,55.1453482796,1249.68 -2.1869581941,55.1434333695,1249.68 -2.1859148286,55.1415956348,1249.68 -2.1843154823,55.1398941272,1249.68 -2.182211607,55.1383835141,1249.68 -2.1796708423,55.1371123239,1249.68 -2.1767748386,55.1361213894,1249.68 -2.1736166351,55.1354425383,1249.68 -2.1702976739,55.1350975733,1249.68 -2.1669245483,55.1350975733,1249.68 -2.1636055872,55.1354425383,1249.68 -2.1604473836,55.1361213894,1249.68 -2.15755138,55.1371123239,1249.68 -2.1550106152,55.1383835141,1249.68 -2.1529067399,55.1398941272,1249.68 -2.1513073936,55.1415956348,1249.68 -2.1502640281,55.1434333695,1249.68 -2.1498102478,55.1453482796,1249.68 -2.149960721,55.1472788247,1249.68 -2.1507106972,55.1491629534,1249.68 -2.1520361497,55.1509400976,1249.68 -2.1538945369,55.1525531206,1249.68 -2.1562261629,55.153950156,1249.68 -2.1589560912,55.1550862772,1249.68 -2.161996553,55.1559249452,1249.68 -2.1652497714,55.1564391851,1249.68 -2.1686111111,55.1566124562,1249.68 + + + + + + EGD509 CAMPBELTOWN + <table border="1" cellpadding="1" cellspacing="0" row_id="1031" txt_name="CAMPBELTOWN"><tr><td>551230N 0053900W following the line of latitude to -<br/>551230N 0050636W -<br/>550706N 0050700W -<br/>545930N 0051542W -<br/>545548N 0052800W -<br/>550630N 0054300W -<br/>551230N 0053900W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information / Booking: CTF311 Operations, Tel: 01923-956371.<br/><br/>Danger Area Authority: HQ Navy.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.65,55.2083333333,16764.0 -5.7166666667,55.1083333333,16764.0 -5.4666666667,54.93,16764.0 -5.2616666667,54.9916666667,16764.0 -5.1166666667,55.1183333333,16764.0 -5.11,55.2083333333,16764.0 -5.245,55.2083333333,16764.0 -5.38,55.2083333333,16764.0 -5.515,55.2083333333,16764.0 -5.65,55.2083333333,16764.0 + + + + + + EGD510A SPADEADAM + <table border="1" cellpadding="1" cellspacing="0" row_id="1649" txt_name="SPADEADAM"><tr><td>551500N 0025256W -<br/>550112N 0024453W -<br/>550900N 0030000W -<br/>551500N 0025400W -<br/>551500N 0025256W <br/>Upper limit: 15000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 5500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 15,000 FT ALT by NOTAM.<br/><br/>Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8821305556,55.25,4572.0 -2.9,55.25,4572.0 -3.0,55.15,4572.0 -2.7480777778,55.019925,4572.0 -2.8821305556,55.25,4572.0 + + + + + + EGD510B SPADEADAM + <table border="1" cellpadding="1" cellspacing="0" row_id="1647" txt_name="SPADEADAM"><tr><td>551500N 0025256W -<br/>551500N 0023951W -<br/>550453N 0021743W -<br/>550417N 0021717W -<br/>550206N 0021640W -<br/>550000N 0022752W -<br/>550000N 0024235W -<br/>550112N 0024453W -<br/>551500N 0025256W <br/>Upper limit: 18000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 5500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.<br/><br/>Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8821305556,55.25,5486.400000000001 -2.7480777778,55.019925,5486.400000000001 -2.7097222222,55.0,5486.400000000001 -2.4644444444,55.0,5486.400000000001 -2.2777777778,55.035,5486.400000000001 -2.2880555556,55.0713888889,5486.400000000001 -2.2952777778,55.0813888889,5486.400000000001 -2.6641666667,55.25,5486.400000000001 -2.8821305556,55.25,5486.400000000001 + + + + + + EGD510C SPADEADAM + <table border="1" cellpadding="1" cellspacing="0" row_id="2094" txt_name="SPADEADAM"><tr><td>A circle, 1.5 NM radius, centred at 550243N 0023526W <br/>Upper limit: 18000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 5500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.<br/><br/>Remarks: When EGD510C is activated in isolation from EGD510B, Unmanned Aircraft System (BVLOS) operations are not permitted.<br/>When EGD510B is activated by NOTAM, EGD510C will also be activated for the same period and to the same altitude.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.59065,55.0702401658,5486.400000000001 -2.5957932319,55.0700649075,5486.400000000001 -2.6008641309,55.0695415973,5486.400000000001 -2.6057913869,55.0686775946,5486.400000000001 -2.6105057207,55.0674850495,5486.400000000001 -2.614940863,55.0659807311,5486.400000000001 -2.6190344894,55.06418579,5486.400000000001 -2.6227290992,55.0621254604,5486.400000000001 -2.6259728243,55.0598287028,5486.400000000001 -2.6287201577,55.0573277963,5486.400000000001 -2.6309325909,55.0546578824,5486.400000000001 -2.6325791506,55.0518564705,5486.400000000001 -2.6336368295,55.0489629096,5486.400000000001 -2.6340909028,55.0460178342,5486.400000000001 -2.6339351282,55.0430625935,5486.400000000001 -2.6331718261,55.0401386701,5486.400000000001 -2.6318118396,55.0372870984,5486.400000000001 -2.6298743751,55.0345478888,5486.400000000001 -2.6273867262,55.031959467,5486.400000000001 -2.6243838853,55.0295581366,5486.400000000001 -2.6209080484,55.0273775709,5486.400000000001 -2.6170080203,55.025448342,5486.400000000001 -2.612738529,55.0237974946,5486.400000000001 -2.6081594582,55.0224481674,5486.400000000001 -2.6033350102,55.0214192711,5486.400000000001 -2.5983328083,55.0207252243,5486.400000000001 -2.5932229534,55.0203757525,5486.400000000001 -2.5880770466,55.0203757525,5486.400000000001 -2.5829671917,55.0207252243,5486.400000000001 -2.5779649898,55.0214192711,5486.400000000001 -2.5731405418,55.0224481674,5486.400000000001 -2.568561471,55.0237974946,5486.400000000001 -2.5642919797,55.025448342,5486.400000000001 -2.5603919516,55.0273775709,5486.400000000001 -2.5569161147,55.0295581366,5486.400000000001 -2.5539132738,55.031959467,5486.400000000001 -2.5514256249,55.0345478888,5486.400000000001 -2.5494881604,55.0372870984,5486.400000000001 -2.5481281739,55.0401386701,5486.400000000001 -2.5473648718,55.0430625935,5486.400000000001 -2.5472090972,55.0460178342,5486.400000000001 -2.5476631705,55.0489629096,5486.400000000001 -2.5487208494,55.0518564705,5486.400000000001 -2.5503674091,55.0546578824,5486.400000000001 -2.5525798423,55.0573277963,5486.400000000001 -2.5553271757,55.0598287028,5486.400000000001 -2.5585709008,55.0621254604,5486.400000000001 -2.5622655106,55.06418579,5486.400000000001 -2.566359137,55.0659807311,5486.400000000001 -2.5707942793,55.0674850495,5486.400000000001 -2.5755086131,55.0686775946,5486.400000000001 -2.5804358691,55.0695415973,5486.400000000001 -2.5855067681,55.0700649075,5486.400000000001 -2.59065,55.0702401658,5486.400000000001 + + + + + + EGD512A OTTERBURN + <table border="1" cellpadding="1" cellspacing="0" row_id="1306" txt_name="OTTERBURN"><tr><td>551418N 0020239W -<br/>551054N 0021311W -<br/>551615N 0022552W -<br/>551857N 0022315W -<br/>551525N 0021352W -<br/>551418N 0020239W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.<br/><br/>Remarks: SI 1971/919 and SI 1980/38.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0441666667,55.2383333333,6705.6 -2.2311111111,55.2569444444,6705.6 -2.3875,55.3158333333,6705.6 -2.4311111111,55.2708333333,6705.6 -2.2197222222,55.1816666667,6705.6 -2.0441666667,55.2383333333,6705.6 + + + + + + EGD512B OTTERBURN + <table border="1" cellpadding="1" cellspacing="0" row_id="1305" txt_name="OTTERBURN"><tr><td>552426N 0021355W -<br/>551719N 0020336W -<br/>551418N 0020239W -<br/>551525N 0021352W -<br/>551857N 0022315W -<br/>552212N 0022009W -<br/>552426N 0021355W <br/>Upper limit: 25000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Vertical Limits: 18,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 25,000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.<br/><br/>Remarks: SI 1971/919 and SI 1980/38.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2319444444,55.4072222222,7620.0 -2.3358333333,55.37,7620.0 -2.3875,55.3158333333,7620.0 -2.2311111111,55.2569444444,7620.0 -2.0441666667,55.2383333333,7620.0 -2.06,55.2886111111,7620.0 -2.2319444444,55.4072222222,7620.0 + + + + + + EGD513A DRURIDGE BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1033" txt_name="DRURIDGE BAY"><tr><td>550200N 0010000W -<br/>552000N 0010640W -<br/>552000N 0002300W -<br/>550200N 0004000W -<br/>550200N 0010000W <br/>Upper limit: FL230<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 134.775 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0,55.0333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -1.0,55.0333333333,7010.400000000001 + + + + + + EGD513B DRURIDGE BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1034" txt_name="DRURIDGE BAY"><tr><td>554400N 0011543W -<br/>554400N 0000726E -<br/>552000N 0001700E -<br/>550200N 0004000W -<br/>552000N 0002300W -<br/>552000N 0010640W -<br/>554400N 0011543W <br/>Upper limit: FL230<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 134.775 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2619444444,55.7333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 0.2833333333,55.3333333333,7010.400000000001 0.1238888889,55.7333333333,7010.400000000001 -1.2619444444,55.7333333333,7010.400000000001 + + + + + + EGD513C DRURIDGE BAY + <table border="1" cellpadding="1" cellspacing="0" row_id="1032" txt_name="DRURIDGE BAY"><tr><td>555000N 0011800W -<br/>555000N 0000500E -<br/>552000N 0001700E -<br/>550200N 0004000W -<br/>550200N 0010000W -<br/>555000N 0011800W <br/>Upper limit: FL100<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 134.775 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3,55.8333333333,3048.0 -1.0,55.0333333333,3048.0 -0.6666666667,55.0333333333,3048.0 0.2833333333,55.3333333333,3048.0 0.0833333333,55.8333333333,3048.0 -1.3,55.8333333333,3048.0 + + + + + + EGD514 COMBAT AIRSPACE + <table border="1" cellpadding="1" cellspacing="0" row_id="14163" txt_name="COMBAT AIRSPACE"><tr><td>564944N 0023059W -<br/>561522N 0003908E -<br/>554828N 0020148E -<br/>542337N 0012225E -<br/>550310N 0010229W -<br/>550419N 0010503W thence anti-clockwise by the arc of a circle radius 21 NM centred on 550217N 0014123W to<br/>551920N 0012007W -<br/>551610N 0013433W -<br/>551426N 0014100W -<br/>551403N 0014229W -<br/>552952N 0023047W -<br/>553928N 0024212W -<br/>560122N 0023945W -<br/>561317N 0025226W -<br/>563754N 0024601W -<br/>564944N 0023059W <br/>Upper limit: FL660<br/>Lower limit: FL85<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz and London Information on 125.475 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.5163368333,56.8287937778,20116.8 -2.7668234167,56.6316858611,20116.8 -2.8739837778,56.2213935,20116.8 -2.6626117778,56.0226490556,20116.8 -2.7031990833,55.6578733611,20116.8 -2.5130380278,55.49769625,20116.8 -1.7079248333,55.2341564444,20116.8 -1.683344,55.2406800833,20116.8 -1.5759322778,55.2693510278,20116.8 -1.3351568333,55.32227475,20116.8 -1.3196354763,55.3157079327,20116.8 -1.304490274,55.3088632909,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2753887059,55.2943685832,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2223387981,55.2623688104,20116.8 -1.2102274184,55.2537886408,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1481271314,55.1981093312,20116.8 -1.13963258,55.1882171739,20116.8 -1.1316917604,55.1781761027,20116.8 -1.1243122408,55.1679962188,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1056084054,55.1367266181,20116.8 -1.1005380561,55.1260949743,20116.8 -1.096058024,55.1153767893,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0414236389,55.0526792778,20116.8 1.3735272222,54.3935690833,20116.8 2.0298775556,55.8078658611,20116.8 0.6521053333,56.2561136389,20116.8 -2.5163368333,56.8287937778,20116.8 + + + + + relativeToGround + + + relativeToGround + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.2213935,2590.8 -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.683344,55.2406800833,2590.8 -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.2943685832,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.2623688104,2590.8 -1.2102274184,55.2537886408,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.1981093312,2590.8 -1.13963258,55.1882171739,2590.8 -1.1316917604,55.1781761027,2590.8 -1.1243122408,55.1679962188,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.1367266181,2590.8 -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.7668234167,56.6316858611,20116.8 -2.5163368333,56.8287937778,20116.8 -2.5163368333,56.8287937778,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.2213935,2590.8 -2.8739837778,56.2213935,20116.8 -2.7668234167,56.6316858611,20116.8 -2.7668234167,56.6316858611,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.8739837778,56.2213935,2590.8 -2.6626117778,56.0226490556,2590.8 -2.6626117778,56.0226490556,20116.8 -2.8739837778,56.2213935,20116.8 -2.8739837778,56.2213935,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.7031990833,55.6578733611,20116.8 -2.6626117778,56.0226490556,20116.8 -2.6626117778,56.0226490556,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -2.5130380278,55.49769625,20116.8 -2.7031990833,55.6578733611,20116.8 -2.7031990833,55.6578733611,2590.8 + + + + + relativeToGround + + + relativeToGround + -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.7079248333,55.2341564444,20116.8 -2.5130380278,55.49769625,20116.8 -2.5130380278,55.49769625,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.7079248333,55.2341564444,2590.8 -1.683344,55.2406800833,2590.8 -1.683344,55.2406800833,20116.8 -1.7079248333,55.2341564444,20116.8 -1.7079248333,55.2341564444,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.683344,55.2406800833,2590.8 -1.5759322778,55.2693510278,2590.8 -1.5759322778,55.2693510278,20116.8 -1.683344,55.2406800833,20116.8 -1.683344,55.2406800833,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3351568333,55.32227475,20116.8 -1.5759322778,55.2693510278,20116.8 -1.5759322778,55.2693510278,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.3196354763,55.3157079327,20116.8 -1.3351568333,55.32227475,20116.8 -1.3351568333,55.32227475,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.304490274,55.3088632909,20116.8 -1.3196354763,55.3157079327,20116.8 -1.3196354763,55.3157079327,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2897364284,55.3017477663,20116.8 -1.304490274,55.3088632909,20116.8 -1.304490274,55.3088632909,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.2943685832,2590.8 -1.2753887059,55.2943685832,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2897364284,55.3017477663,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2753887059,55.2943685832,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2614614361,55.2867332297,20116.8 -1.2753887059,55.2943685832,20116.8 -1.2753887059,55.2943685832,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2479684983,55.2788494494,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2614614361,55.2867332297,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2349233067,55.2707252331,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2479684983,55.2788494494,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.2623688104,2590.8 -1.2223387981,55.2623688104,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2349233067,55.2707252331,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2223387981,55.2623688104,2590.8 -1.2102274184,55.2537886408,2590.8 -1.2102274184,55.2537886408,20116.8 -1.2223387981,55.2623688104,20116.8 -1.2223387981,55.2623688104,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.2102274184,55.2537886408,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1986011112,55.2449934046,20116.8 -1.2102274184,55.2537886408,20116.8 -1.2102274184,55.2537886408,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1874713062,55.2359919941,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1986011112,55.2449934046,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1768489084,55.2267935037,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1874713062,55.2359919941,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1667442882,55.2174072208,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1768489084,55.2267935037,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1571672715,55.2078426155,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1667442882,55.2174072208,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.1981093312,2590.8 -1.1481271314,55.1981093312,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1571672715,55.2078426155,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1481271314,55.1981093312,2590.8 -1.13963258,55.1882171739,2590.8 -1.13963258,55.1882171739,20116.8 -1.1481271314,55.1981093312,20116.8 -1.1481271314,55.1981093312,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.13963258,55.1882171739,2590.8 -1.1316917604,55.1781761027,2590.8 -1.1316917604,55.1781761027,20116.8 -1.13963258,55.1882171739,20116.8 -1.13963258,55.1882171739,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1316917604,55.1781761027,2590.8 -1.1243122408,55.1679962188,2590.8 -1.1243122408,55.1679962188,20116.8 -1.1316917604,55.1781761027,20116.8 -1.1316917604,55.1781761027,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1243122408,55.1679962188,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1175010074,55.1576877554,20116.8 -1.1243122408,55.1679962188,20116.8 -1.1243122408,55.1679962188,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1112644597,55.1472610668,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1175010074,55.1576877554,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.1367266181,2590.8 -1.1056084054,55.1367266181,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1112644597,55.1472610668,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1056084054,55.1367266181,2590.8 -1.1005380561,55.1260949743,2590.8 -1.1005380561,55.1260949743,20116.8 -1.1056084054,55.1367266181,20116.8 -1.1056084054,55.1367266181,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.096058024,55.1153767893,20116.8 -1.1005380561,55.1260949743,20116.8 -1.1005380561,55.1260949743,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0921723192,55.1045827952,20116.8 -1.096058024,55.1153767893,20116.8 -1.096058024,55.1153767893,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0888843473,55.0937237913,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0921723192,55.1045827952,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0861969081,55.0828106334,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0888843473,55.0937237913,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0841121944,55.0718542222,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0861969081,55.0828106334,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 -1.0414236389,55.0526792778,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0841121944,55.0718542222,2590.8 + + + + + relativeToGround + + + relativeToGround + -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 1.3735272222,54.3935690833,20116.8 -1.0414236389,55.0526792778,20116.8 -1.0414236389,55.0526792778,2590.8 + + + + + relativeToGround + + + relativeToGround + 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 2.0298775556,55.8078658611,20116.8 1.3735272222,54.3935690833,20116.8 1.3735272222,54.3935690833,2590.8 + + + + + relativeToGround + + + relativeToGround + 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 0.6521053333,56.2561136389,20116.8 2.0298775556,55.8078658611,20116.8 2.0298775556,55.8078658611,2590.8 + + + + + relativeToGround + + + relativeToGround + 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 -2.5163368333,56.8287937778,20116.8 0.6521053333,56.2561136389,20116.8 0.6521053333,56.2561136389,2590.8 + + + + + + + EGD601 GARELOCHHEAD + <table border="1" cellpadding="1" cellspacing="0" row_id="1247" txt_name="GARELOCHHEAD"><tr><td>560805N 0044636W -<br/>560505N 0044656W -<br/>560440N 0044740W -<br/>560547N 0044912W -<br/>560706N 0044912W -<br/>560805N 0044636W <br/>Upper limit: 4000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: Scottish Information on 119.875 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01412-248123.<br/><br/>Danger Area Authority: DIO.<br/><br/>Remarks: UAS BVLOS will not be conducted above 1500 FT ALT.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.7766666667,56.1347222222,1219.2 -4.82,56.1183333333,1219.2 -4.82,56.0963888889,1219.2 -4.7944444444,56.0777777778,1219.2 -4.7822222222,56.0847222222,1219.2 -4.7766666667,56.1347222222,1219.2 + + + + + + EGD604 BARRY BUDDON + <table border="1" cellpadding="1" cellspacing="0" row_id="1035" txt_name="BARRY BUDDON"><tr><td>562849N 0024849W -<br/>562957N 0024010W -<br/>562735N 0023943W -<br/>562738N 0024829W -<br/>562849N 0024849W <br/>Upper limit: 9000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 1500 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 9000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: Leuchars APP on 126.500 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-103426.<br/><br/>Remarks: SI 1973/1428. UAS BVLOS will not be conducted above 3000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8136111111,56.4802777778,2743.2000000000003 -2.8080555556,56.4605555556,2743.2000000000003 -2.6619444444,56.4597222222,2743.2000000000003 -2.6694444444,56.4991666667,2743.2000000000003 -2.8136111111,56.4802777778,2743.2000000000003 + + + + + + EGD613A CENTRAL COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1036" txt_name="CENTRAL COMPLEX"><tr><td>574421N 0002631E -<br/>571940N 0004851E -<br/>564725N 0013559W -<br/>571447N 0014618W -<br/>574421N 0002631E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Swanwick Military on 136.375 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 0.4419305556,57.7391472222,20116.8 -1.7715583333,57.2462805556,20116.8 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.4419305556,57.7391472222,20116.8 + + + + + relativeToGround + + + relativeToGround + 0.4419305556,57.7391472222,3048.0 -1.7715583333,57.2462805556,3048.0 -1.5996,56.7901638889,3048.0 0.8140888889,57.32785,3048.0 0.4419305556,57.7391472222,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.4419305556,57.7391472222,3048.0 -1.7715583333,57.2462805556,3048.0 -1.7715583333,57.2462805556,20116.8 0.4419305556,57.7391472222,20116.8 0.4419305556,57.7391472222,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.7715583333,57.2462805556,3048.0 -1.5996,56.7901638889,3048.0 -1.5996,56.7901638889,20116.8 -1.7715583333,57.2462805556,20116.8 -1.7715583333,57.2462805556,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.5996,56.7901638889,3048.0 0.8140888889,57.32785,3048.0 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.8140888889,57.32785,3048.0 0.4419305556,57.7391472222,3048.0 0.4419305556,57.7391472222,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048.0 + + + + + + + EGD613B CENTRAL COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1037" txt_name="CENTRAL COMPLEX"><tr><td>571940N 0004851E -<br/>565256N 0011225E -<br/>564725N 0013559W -<br/>571940N 0004851E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Swanwick Military on 136.375 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 0.8140888889,57.32785,20116.8 + + + + + relativeToGround + + + relativeToGround + 0.8140888889,57.32785,3048.0 -1.5996,56.7901638889,3048.0 1.2068416667,56.8823361111,3048.0 0.8140888889,57.32785,3048.0 + + + + + relativeToGround + + + relativeToGround + 0.8140888889,57.32785,3048.0 -1.5996,56.7901638889,3048.0 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.5996,56.7901638889,3048.0 1.2068416667,56.8823361111,3048.0 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,3048.0 0.8140888889,57.32785,3048.0 0.8140888889,57.32785,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048.0 + + + + + + + EGD613C CENTRAL COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1038" txt_name="CENTRAL COMPLEX"><tr><td>565256N 0011225E -<br/>561750N 0012507W -<br/>564725N 0013559W -<br/>565256N 0011225E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Swanwick Military on 136.375 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,3048.0 -1.5996,56.7901638889,3048.0 -1.4184805556,56.2971694444,3048.0 1.2068416667,56.8823361111,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,3048.0 -1.5996,56.7901638889,3048.0 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.5996,56.7901638889,3048.0 -1.4184805556,56.2971694444,3048.0 -1.4184805556,56.2971694444,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.4184805556,56.2971694444,3048.0 1.2068416667,56.8823361111,3048.0 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048.0 + + + + + + + EGD613D CENTRAL COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1632" txt_name="CENTRAL COMPLEX"><tr><td>565256N 0011225E -<br/>560344N 0015411E -<br/>560509N 0002907W -<br/>561750N 0012507W -<br/>565256N 0011225E <br/>Upper limit: FL660<br/>Lower limit: FL100<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.<br/><br/>Service: SUAAIS: Swanwick Military on 136.375 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -0.4851527778,56.0857027778,20116.8 1.9031472222,56.0623555556,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,3048.0 -1.4184805556,56.2971694444,3048.0 -0.4851527778,56.0857027778,3048.0 1.9031472222,56.0623555556,3048.0 1.2068416667,56.8823361111,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.2068416667,56.8823361111,3048.0 -1.4184805556,56.2971694444,3048.0 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048.0 + + + + + relativeToGround + + + relativeToGround + -1.4184805556,56.2971694444,3048.0 -0.4851527778,56.0857027778,3048.0 -0.4851527778,56.0857027778,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048.0 + + + + + relativeToGround + + + relativeToGround + -0.4851527778,56.0857027778,3048.0 1.9031472222,56.0623555556,3048.0 1.9031472222,56.0623555556,20116.8 -0.4851527778,56.0857027778,20116.8 -0.4851527778,56.0857027778,3048.0 + + + + + relativeToGround + + + relativeToGround + 1.9031472222,56.0623555556,3048.0 1.2068416667,56.8823361111,3048.0 1.2068416667,56.8823361111,20116.8 1.9031472222,56.0623555556,20116.8 1.9031472222,56.0623555556,3048.0 + + + + + + + EGD701A HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1633" txt_name="HEBRIDES"><tr><td>573347N 0074803W -<br/>572253N 0072531W -<br/>572324N 0072233W -<br/>572147N 0072116W -<br/>571056N 0072253W -<br/>571034N 0073131W -<br/>570200N 0073421W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -<br/>573347N 0074803W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.8008333333,57.5630555556,30449.52 -7.8147936092,57.5556144002,30449.52 -7.8282732985,57.5479228699,30449.52 -7.841261266,57.5399919141,30449.52 -7.8537430548,57.5318305591,30449.52 -7.8657048125,57.5234480871,30449.52 -7.877133306,57.5148540252,30449.52 -7.8880159355,57.5060581345,30449.52 -7.8983407475,57.4970703978,30449.52 -7.9080964477,57.4879010084,30449.52 -7.9172724118,57.4785603579,30449.52 -7.9258586962,57.4690590239,30449.52 -7.9338460477,57.4594077576,30449.52 -7.9412259119,57.4496174713,30449.52 -7.9479904416,57.4396992258,30449.52 -7.9541325028,57.4296642173,30449.52 -7.9596456814,57.4195237646,30449.52 -7.9645242879,57.4092892961,30449.52 -7.9687633616,57.3989723365,30449.52 -7.972358674,57.3885844937,30449.52 -7.975306731,57.3781374455,30449.52 -7.9776047746,57.3676429262,30449.52 -7.9792507833,57.3571127135,30449.52 -7.9802434722,57.3465586152,30449.52 -7.9805822915,57.3359924554,30449.52 -7.980267425,57.325426062,30449.52 -7.979299787,57.3148712527,30449.52 -7.9776810193,57.3043398224,30449.52 -7.9754134861,57.2938435297,30449.52 -7.9725002697,57.283394084,30449.52 -7.9689451642,57.2730031328,30449.52 -7.9647526688,57.2626822485,30449.52 -7.959927981,57.2524429158,30449.52 -7.9544769877,57.2422965194,30449.52 -7.9484062576,57.2322543314,30449.52 -7.9417230308,57.222327499,30449.52 -7.9344352093,57.2125270325,30449.52 -7.9265513463,57.2028637936,30449.52 -7.9180806346,57.1933484835,30449.52 -7.9090328952,57.1839916314,30449.52 -7.8994185645,57.1748035833,30449.52 -7.8892486813,57.1657944914,30449.52 -7.8785348735,57.1569743024,30449.52 -7.8672893439,57.148352748,30449.52 -7.8555248557,57.1399393337,30449.52 -7.8432547174,57.1317433295,30449.52 -7.8304927676,57.1237737598,30449.52 -7.8172533586,57.116039394,30449.52 -7.8035513406,57.1085487375,30449.52 -7.7894020448,57.1013100226,30449.52 -7.7748212661,57.0943312,30449.52 -7.7598252458,57.0876199308,30449.52 -7.7444306541,57.0811835783,30449.52 -7.7286545713,57.0750292004,30449.52 -7.71251447,57.0691635427,30449.52 -7.696028196,57.063593031,30449.52 -7.6792139495,57.058323765,30449.52 -7.6620902657,57.0533615124,30449.52 -7.6446759953,57.0487117023,30449.52 -7.6269902851,57.0443794202,30449.52 -7.6090525576,57.0403694026,30449.52 -7.5908824912,57.0366860321,30449.52 -7.5725,57.0333333333,30449.52 -7.5252777778,57.1761111111,30449.52 -7.3813888889,57.1822222222,30449.52 -7.3544444444,57.3630555556,30449.52 -7.3758333333,57.39,30449.52 -7.4252777778,57.3813888889,30449.52 -7.8008333333,57.5630555556,30449.52 + + + + + + EGD701B HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1039" txt_name="HEBRIDES"><tr><td>570200N 0073421W -<br/>565713N 0073556W -<br/>571703N 0092047W -<br/>574801N 0092039W -<br/>574514N 0083032W -<br/>574224N 0080606W -<br/>573347N 0074803W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -<br/>570200N 0073421W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5725,57.0333333333,30449.52 -7.5908806376,57.0366888943,30449.52 -7.6090505306,57.0403722297,30449.52 -7.6269880869,57.0443822091,30449.52 -7.6446736282,57.0487144499,30449.52 -7.6620877322,57.0533642157,30449.52 -7.6792112525,57.058326421,30449.52 -7.6960253382,57.0635956367,30449.52 -7.7125114546,57.0691660953,30449.52 -7.7286514014,57.075031697,30449.52 -7.7444273331,57.0811860162,30449.52 -7.7598217773,57.0876223072,30449.52 -7.7748176538,57.0943335124,30449.52 -7.7893982926,57.1013122683,30449.52 -7.8035474526,57.1085509141,30449.52 -7.817249339,57.1160414991,30449.52 -7.8304886206,57.123775791,30449.52 -7.8432504477,57.1317452846,30449.52 -7.8555204677,57.1399412104,30449.52 -7.8672848425,57.1483545443,30449.52 -7.8785302635,57.1569760164,30449.52 -7.8892439677,57.165796121,30449.52 -7.8994137525,57.1748051268,30449.52 -7.9090279901,57.1839930869,30449.52 -7.9180756416,57.1933498495,30449.52 -7.9265462709,57.2028650685,30449.52 -7.9344300571,57.2125282149,30449.52 -7.9417178074,57.2223285875,30449.52 -7.9484009688,57.2322553248,30449.52 -7.9544716393,57.2422974166,30449.52 -7.9599225788,57.2524437158,30449.52 -7.964747219,57.2626829503,30449.52 -7.9689396726,57.2730037357,30449.52 -7.9724947425,57.2833945872,30449.52 -7.9754079293,57.2938439326,30449.52 -7.9776754391,57.3043401245,30449.52 -7.9792941897,57.3148714537,30449.52 -7.9802618168,57.3254261616,30449.52 -7.9805766787,57.3359924536,30449.52 -7.980237861,57.3465585118,30449.52 -7.9792451801,57.3571125087,30449.52 -7.9775991856,57.3676426201,30449.52 -7.9753011625,57.3781370385,30449.52 -7.9723531322,57.3885839862,30449.52 -7.9687578529,57.3989717291,30449.52 -7.9645188184,57.4092885894,30449.52 -7.9596402574,57.4195229594,30449.52 -7.9541271304,57.4296633144,30449.52 -7.9479851269,57.4396982262,30449.52 -7.941220661,57.4496163762,30449.52 -7.9338408665,57.4594065681,30449.52 -7.9258535907,57.4690577413,30449.52 -7.9172673878,57.4785589837,30449.52 -7.9080915109,57.4878995441,30449.52 -7.8983359036,57.497068845,30449.52 -7.88801119,57.5060564949,30449.52 -7.8771286645,57.5148523008,30449.52 -7.8657002803,57.5234462797,30449.52 -7.8537386371,57.5318286708,30449.52 -7.8412569678,57.5399899469,30449.52 -7.8282691249,57.547920826,30449.52 -7.814789565,57.555612282,30449.52 -7.8008333333,57.5630555556,30449.52 -8.1016944444,57.7065416667,30449.52 -8.5088277778,57.7539222222,30449.52 -9.3442027778,57.8003527778,30449.52 -9.3463777778,57.2840638889,30449.52 -7.5988888889,56.9536111111,30449.52 -7.5725,57.0333333333,30449.52 + + + + + + EGD701C HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1040" txt_name="HEBRIDES"><tr><td>574801N 0092039W -<br/>575639N 0081032W -<br/>575154N 0074532W -<br/>573809N 0073422W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to<br/>573347N 0074803W -<br/>574224N 0080606W -<br/>574514N 0083032W -<br/>574801N 0092039W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-9.3442027778,57.8003527778,30449.52 -8.5088277778,57.7539222222,30449.52 -8.1016944444,57.7065416667,30449.52 -7.8008333333,57.5630555556,30449.52 -7.786893946,57.5700722445,30449.52 -7.772476361,57.5768067724,30449.52 -7.7576539429,57.5832844235,30449.52 -7.7424424392,57.5894982237,30449.52 -7.7268580417,57.5954414793,30449.52 -7.7109173688,57.601107785,30449.52 -7.6946374473,57.6064910309,30449.52 -7.6780356935,57.6115854099,30449.52 -7.6611298942,57.6163854238,30449.52 -7.6439381861,57.6208858901,30449.52 -7.6264790362,57.625081948,30449.52 -7.6087712203,57.6289690637,30449.52 -7.590833802,57.6325430357,30449.52 -7.5726861111,57.6358,30449.52 -7.7588888889,57.865,30449.52 -8.1755777778,57.9442055556,30449.52 -9.3442027778,57.8003527778,30449.52 + + + + + + EGD701D HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1041" txt_name="HEBRIDES"><tr><td>571703N 0092047W -<br/>565801N 0074000W -<br/>564302N 0074000W -<br/>565603N 0090000W -<br/>571703N 0092047W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-9.3463777778,57.2840638889,30449.52 -9.0,56.9342638889,30449.52 -7.6666666667,56.7172722222,30449.52 -7.6666666667,56.9669944444,30449.52 -9.3463777778,57.2840638889,30449.52 + + + + + + EGD701E HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1650" txt_name="HEBRIDES"><tr><td>582859N 0094100W following the line of latitude to -<br/>582859N 0084939W -<br/>574923N 0071500W -<br/>574128N 0073703W -<br/>575154N 0074532W -<br/>575639N 0081032W -<br/>575411N 0083112W -<br/>580439N 0085353W -<br/>582859N 0094100W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-9.6834222222,58.4831388889,30449.52 -8.8980555556,58.0775,30449.52 -8.5201277778,57.9030305556,30449.52 -8.1755777778,57.9442055556,30449.52 -7.7588888889,57.865,30449.52 -7.6173694444,57.6910777778,30449.52 -7.25,57.8231472222,30449.52 -8.8276361111,58.4831388889,30449.52 -8.9987933333,58.4831388889,30449.52 -9.1699505556,58.4831388889,30449.52 -9.3411077778,58.4831388889,30449.52 -9.512265,58.4831388889,30449.52 -9.6834222222,58.4831388889,30449.52 + + + + + + EGD701F HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1042" txt_name="HEBRIDES"><tr><td>593000N 0100000W -<br/>584715N 0074914W -<br/>582525N 0070835W -<br/>574923N 0071500W -<br/>582859N 0084939W following the line of latitude to -<br/>582859N 0100000W -<br/>593000N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,59.5,30449.52 -10.0,58.4831388889,30449.52 -9.8325194444,58.4831388889,30449.52 -9.6650388889,58.4831388889,30449.52 -9.4975583333,58.4831388889,30449.52 -9.3300777778,58.4831388889,30449.52 -9.1625972222,58.4831388889,30449.52 -8.9951166667,58.4831388889,30449.52 -8.8276361111,58.4831388889,30449.52 -7.25,57.8231472222,30449.52 -7.1430638889,58.4235972222,30449.52 -7.8206222222,58.7873638889,30449.52 -10.0,59.5,30449.52 + + + + + + EGD701G HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1043" txt_name="HEBRIDES"><tr><td>582859N 0100000W following the line of latitude to -<br/>582859N 0094100W -<br/>580439N 0085353W -<br/>575411N 0083112W -<br/>574801N 0092039W -<br/>571703N 0092047W -<br/>573301N 0100000W -<br/>582859N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,58.4831388889,30449.52 -10.0,57.5501444444,30449.52 -9.3463777778,57.2840638889,30449.52 -9.3442027778,57.8003527778,30449.52 -8.5201277778,57.9030305556,30449.52 -8.8980555556,58.0775,30449.52 -9.6834222222,58.4831388889,30449.52 -9.8417111111,58.4831388889,30449.52 -10.0,58.4831388889,30449.52 + + + + + + EGD701H HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1044" txt_name="HEBRIDES"><tr><td>573301N 0100000W -<br/>571703N 0092047W -<br/>565603N 0090000W -<br/>571500N 0100000W -<br/>573301N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,57.5501444444,30449.52 -10.0,57.25,30449.52 -9.0,56.9342638889,30449.52 -9.3463777778,57.2840638889,30449.52 -10.0,57.5501444444,30449.52 + + + + + + EGD701I HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1045" txt_name="HEBRIDES"><tr><td>571500N 0100000W -<br/>565603N 0090000W -<br/>564302N 0074000W -<br/>563510N 0074307W -<br/>563524N 0083728W -<br/>564548N 0100000W -<br/>571500N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,57.25,30449.52 -10.0,56.7633694444,30449.52 -8.6245138889,56.5898861111,30449.52 -7.7185305556,56.5859805556,30449.52 -7.6666666667,56.7172722222,30449.52 -9.0,56.9342638889,30449.52 -10.0,57.25,30449.52 + + + + + + EGD701J HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1046" txt_name="HEBRIDES"><tr><td>564548N 0100000W -<br/>563524N 0083728W -<br/>563510N 0074307W -<br/>560339N 0074415W -<br/>563523N 0100000W -<br/>564548N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,56.7633694444,30449.52 -10.0,56.5896416667,30449.52 -7.7374527778,56.0608027778,30449.52 -7.7185305556,56.5859805556,30449.52 -8.6245138889,56.5898861111,30449.52 -10.0,56.7633694444,30449.52 + + + + + + EGD701K HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1047" txt_name="HEBRIDES"><tr><td>563523N 0100000W -<br/>560339N 0074415W -<br/>555107N 0080000W following the line of latitude to -<br/>555107N 0080331W -<br/>562630N 0100000W -<br/>563523N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,56.5896416667,30449.52 -10.0,56.4417388889,30449.52 -8.0585555556,55.8519,30449.52 -8.0,55.8519,30449.52 -7.7374527778,56.0608027778,30449.52 -10.0,56.5896416667,30449.52 + + + + + + EGD701L HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1048" txt_name="HEBRIDES"><tr><td>562630N 0100000W -<br/>560435N 0084640W -<br/>560530N 0100000W -<br/>562630N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,56.4417388889,30449.52 -10.0,56.0917611111,30449.52 -8.7777972222,56.0762722222,30449.52 -10.0,56.4417388889,30449.52 + + + + + + EGD701M HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1049" txt_name="HEBRIDES"><tr><td>560530N 0100000W -<br/>560435N 0084640W -<br/>555107N 0080331W following the line of latitude to -<br/>555107N 0080000W -<br/>554000N 0080000W following the line of latitude to -<br/>554000N 0092508W -<br/>554516N 0100000W -<br/>560530N 0100000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-10.0,56.0917611111,30449.52 -10.0,55.7545083333,30449.52 -9.4188888889,55.6666666667,30449.52 -9.2612345679,55.6666666667,30449.52 -9.1035802469,55.6666666667,30449.52 -8.9459259259,55.6666666667,30449.52 -8.7882716049,55.6666666667,30449.52 -8.630617284,55.6666666667,30449.52 -8.472962963,55.6666666667,30449.52 -8.315308642,55.6666666667,30449.52 -8.157654321,55.6666666667,30449.52 -8.0,55.6666666667,30449.52 -8.0,55.8519,30449.52 -8.0585555556,55.8519,30449.52 -8.7777972222,56.0762722222,30449.52 -10.0,56.0917611111,30449.52 + + + + + + EGD701N HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1050" txt_name="HEBRIDES"><tr><td>563148N 0114510W -<br/>560530N 0100000W -<br/>554516N 0100000W -<br/>555352N 0110000W -<br/>563148N 0114510W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-11.7529138889,56.53005,30449.52 -11.0,55.8977805556,30449.52 -10.0,55.7545083333,30449.52 -10.0,56.0917611111,30449.52 -11.7529138889,56.53005,30449.52 + + + + + + EGD701O HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1051" txt_name="HEBRIDES"><tr><td>570000N 0120000W -<br/>562630N 0100000W -<br/>560530N 0100000W -<br/>563148N 0114510W -<br/>564357N 0120000W -<br/>570000N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,57.0,30449.52 -12.0,56.7324472222,30449.52 -11.7529138889,56.53005,30449.52 -10.0,56.0917611111,30449.52 -10.0,56.4417388889,30449.52 -12.0,57.0,30449.52 + + + + + + EGD701P HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1052" txt_name="HEBRIDES"><tr><td>572125N 0120000W -<br/>565038N 0104118W -<br/>564548N 0100000W -<br/>562630N 0100000W -<br/>570000N 0120000W -<br/>572125N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,57.3568694444,30449.52 -12.0,57.0,30449.52 -10.0,56.4417388889,30449.52 -10.0,56.7633694444,30449.52 -10.6883611111,56.8439194444,30449.52 -12.0,57.3568694444,30449.52 + + + + + + EGD701Q HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1053" txt_name="HEBRIDES"><tr><td>572125N 0120000W -<br/>571500N 0100000W -<br/>564548N 0100000W -<br/>565038N 0104118W -<br/>572125N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,57.3568694444,30449.52 -10.6883611111,56.8439194444,30449.52 -10.0,56.7633694444,30449.52 -10.0,57.25,30449.52 -12.0,57.3568694444,30449.52 + + + + + + EGD701R HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1054" txt_name="HEBRIDES"><tr><td>580135N 0120000W -<br/>573301N 0100000W -<br/>571500N 0100000W -<br/>572125N 0120000W -<br/>580135N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,58.0264222222,30449.52 -12.0,57.3568694444,30449.52 -10.0,57.25,30449.52 -10.0,57.5501444444,30449.52 -12.0,58.0264222222,30449.52 + + + + + + EGD701S HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="944" txt_name="HEBRIDES"><tr><td>584514N 0120000W -<br/>582859N 0100000W -<br/>573301N 0100000W -<br/>580135N 0120000W -<br/>584514N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,58.7539083333,30449.52 -12.0,58.0264222222,30449.52 -10.0,57.5501444444,30449.52 -10.0,58.4831388889,30449.52 -12.0,58.7539083333,30449.52 + + + + + + EGD701T HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="945" txt_name="HEBRIDES"><tr><td>593000N 0120000W following the line of latitude to -<br/>593000N 0100000W -<br/>582859N 0100000W -<br/>584514N 0120000W -<br/>593000N 0120000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-12.0,59.5,30449.52 -12.0,58.7539083333,30449.52 -10.0,58.4831388889,30449.52 -10.0,59.5,30449.52 -10.1666666667,59.5,30449.52 -10.3333333333,59.5,30449.52 -10.5,59.5,30449.52 -10.6666666667,59.5,30449.52 -10.8333333333,59.5,30449.52 -11.0,59.5,30449.52 -11.1666666667,59.5,30449.52 -11.3333333333,59.5,30449.52 -11.5,59.5,30449.52 -11.6666666667,59.5,30449.52 -11.8333333333,59.5,30449.52 -12.0,59.5,30449.52 + + + + + + EGD701U HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="946" txt_name="HEBRIDES"><tr><td>590000N 0130000W -<br/>593000N 0120000W -<br/>584514N 0120000W -<br/>585236N 0130000W -<br/>590000N 0130000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-13.0,59.0,30449.52 -13.0,58.8765361111,30449.52 -12.0,58.7539083333,30449.52 -12.0,59.5,30449.52 -13.0,59.0,30449.52 + + + + + + EGD701V HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="947" txt_name="HEBRIDES"><tr><td>585236N 0130000W -<br/>584514N 0120000W -<br/>580135N 0120000W -<br/>581454N 0130000W -<br/>585236N 0130000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-13.0,58.8765361111,30449.52 -13.0,58.2481972222,30449.52 -12.0,58.0264222222,30449.52 -12.0,58.7539083333,30449.52 -13.0,58.8765361111,30449.52 + + + + + + EGD701W HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="948" txt_name="HEBRIDES"><tr><td>581454N 0130000W -<br/>580135N 0120000W -<br/>572125N 0120000W -<br/>573126N 0130000W -<br/>581454N 0130000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-13.0,58.2481972222,30449.52 -13.0,57.5239055556,30449.52 -12.0,57.3568694444,30449.52 -12.0,58.0264222222,30449.52 -13.0,58.2481972222,30449.52 + + + + + + EGD701X HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="949" txt_name="HEBRIDES"><tr><td>573126N 0130000W -<br/>572125N 0120000W -<br/>564357N 0120000W -<br/>573126N 0130000W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-13.0,57.5239055556,30449.52 -12.0,56.7324472222,30449.52 -12.0,57.3568694444,30449.52 -13.0,57.5239055556,30449.52 + + + + + + EGD701Y HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="950" txt_name="HEBRIDES"><tr><td>573809N 0073422W -<br/>572324N 0072233W -<br/>572253N 0072531W -<br/>573347N 0074803W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -<br/>573809N 0073422W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5726861111,57.6358,30449.52 -7.5908058302,57.6325005233,30449.52 -7.6087406711,57.6289270654,30449.52 -7.6264459435,57.6250405088,30449.52 -7.6439025864,57.6208450543,30449.52 -7.6610918269,57.6163452351,30449.52 -7.6779952008,57.6115459113,30449.52 -7.6945945737,57.6064522647,30449.52 -7.7108721616,57.6010697925,30449.52 -7.7268105508,57.5954043011,30449.52 -7.7423927169,57.5894618995,30449.52 -7.7576020438,57.583248992,30449.52 -7.7724223421,57.5767722714,30449.52 -7.7868378667,57.5700387107,30449.52 -7.8008333333,57.5630555556,30449.52 -7.4252777778,57.3813888889,30449.52 -7.3758333333,57.39,30449.52 -7.5726861111,57.6358,30449.52 + + + + + + EGD702 FORT GEORGE + <table border="1" cellpadding="1" cellspacing="0" row_id="1652" txt_name="FORT GEORGE"><tr><td>573617N 0040047W -<br/>573449N 0040128W -<br/>573440N 0040257W -<br/>573456N 0040438W -<br/>573534N 0040338W -<br/>573617N 0040047W <br/>Upper limit: 2100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).<br/><br/>Service: SUAAIS: Inverness APP/Tower on 122.605 MHz when open; at other times Scottish Information on 134.850 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-108124/108114.<br/><br/>Remarks: SI 1940/30.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0130555556,57.6047222222,640.08 -4.0605555556,57.5927777778,640.08 -4.0772222222,57.5822222222,640.08 -4.0491666667,57.5777777778,640.08 -4.0244444444,57.5802777778,640.08 -4.0130555556,57.6047222222,640.08 + + + + + + EGD703 TAIN + <table border="1" cellpadding="1" cellspacing="0" row_id="1653" txt_name="TAIN"><tr><td>575224N 0033030W -<br/>575054N 0034630W -<br/>574500N 0035500W -<br/>574500N 0040254W -<br/>575136N 0040812W -<br/>580324N 0034436W -<br/>580700N 0033700W -<br/>580300N 0033000W -<br/>575224N 0033000W -<br/>575224N 0033030W <br/>Upper limit: 22000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Vertical Limits: 15,000 FT ALT.<br/><br/>Vertical Limits: OCNL notified to altitudes up to 22,000 FT ALT by NOTAM.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Para Dropping / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Tain Range on 122.750 MHz when open. SUAAIS: Tain Range on 122.750 MHz when open; at other times Scottish Information on 134.850 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range ATC, Tel: 01862-892185 Ext 4945.<br/><br/>Remarks: Aircraft wishing to use Dornoch or Easter Aerodromes during range opening hours are to contact Tain Range on 122.750 MHz prior to entering the range. Associated aircraft operations outside area boundary. SI 1940/684. UAS BVLOS will not be conducted above 2000 FT ALT.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.5083333333,57.8733333333,6705.6 -3.5,57.8733333333,6705.6 -3.5,58.05,6705.6 -3.6166666667,58.1166666667,6705.6 -3.7433333333,58.0566666667,6705.6 -4.1366666667,57.86,6705.6 -4.0483333333,57.75,6705.6 -3.9166666667,57.75,6705.6 -3.775,57.8483333333,6705.6 -3.5083333333,57.8733333333,6705.6 + + + + + + EGD704 HEBRIDES + <table border="1" cellpadding="1" cellspacing="0" row_id="1651" txt_name="HEBRIDES"><tr><td>573727N 0071811W -<br/>573143N 0071055W -<br/>572625N 0072457W -<br/>573305N 0073017W -<br/>573727N 0071811W <br/>Upper limit: 10000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.<br/><br/>Service: SUACS: Benbecula Approach on 119.205 MHz when open. SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01870-604449.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3030555556,57.6241666667,3048.0 -7.5047222222,57.5513888889,3048.0 -7.4158333333,57.4402777778,3048.0 -7.1819444444,57.5286111111,3048.0 -7.3030555556,57.6241666667,3048.0 + + + + + + EGD710 RAASAY + <table border="1" cellpadding="1" cellspacing="0" row_id="951" txt_name="RAASAY"><tr><td>572200N 0054927W -<br/>572200N 0055935W - then along the east coast of Raasay and Rona in an northerly direction to<br/>573500N 0055800W -<br/>573800N 0055800W -<br/>573800N 0055000W -<br/>573445N 0055000W - then along the west coast of the Applecross peninsula in an southerly direction to -<br/>572200N 0054927W <br/>Upper limit: 1500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards / Unmanned Aircraft System (VLOS/BVLOS).<br/><br/>Service: SUAAIS: Scottish Information on 127.275 MHz.<br/><br/>Contact: Pre-flight information: Range Control, Tel: 01397-436720.<br/><br/>Remarks: SI 2016/654.<br/><br/>Danger Area Authority: DE&S.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.8241666667,57.3666666667,457.20000000000005 -5.8226555556,57.3676027778,457.20000000000005 -5.8224527778,57.3688666667,457.20000000000005 -5.8234638889,57.3721638889,457.20000000000005 -5.8240722222,57.373225,457.20000000000005 -5.8225916667,57.3749777778,457.20000000000005 -5.8243083333,57.3770833333,457.20000000000005 -5.8253972222,57.37795,457.20000000000005 -5.8264361111,57.3815166667,457.20000000000005 -5.8251666667,57.3837111111,457.20000000000005 -5.8259833333,57.3867444444,457.20000000000005 -5.8266111111,57.3879833333,457.20000000000005 -5.8284305556,57.3894583333,457.20000000000005 -5.829925,57.39085,457.20000000000005 -5.8288083333,57.3919722222,457.20000000000005 -5.8265416667,57.3913055556,457.20000000000005 -5.8242083333,57.3913027778,457.20000000000005 -5.8240833333,57.3894555556,457.20000000000005 -5.8210777778,57.3876138889,457.20000000000005 -5.818275,57.3894972222,457.20000000000005 -5.8188222222,57.3915472222,457.20000000000005 -5.8205416667,57.3936527778,457.20000000000005 -5.8208555556,57.3950833333,457.20000000000005 -5.8189972222,57.3980166667,457.20000000000005 -5.8183916667,57.4014888889,457.20000000000005 -5.8152333333,57.4009194444,457.20000000000005 -5.8142611111,57.399725,457.20000000000005 -5.8131638889,57.3978333333,457.20000000000005 -5.8121638889,57.3950944444,457.20000000000005 -5.8105222222,57.3954944444,457.20000000000005 -5.8097055556,57.393875,457.20000000000005 -5.8080416667,57.3940694444,457.20000000000005 -5.8062666667,57.3918833333,457.20000000000005 -5.803125,57.391125,457.20000000000005 -5.803125,57.3927444444,457.20000000000005 -5.8058944444,57.3953583333,457.20000000000005 -5.8079805556,57.3961916667,457.20000000000005 -5.8087861111,57.3991361111,457.20000000000005 -5.8064416667,57.3990277778,457.20000000000005 -5.8055472222,57.4000444444,457.20000000000005 -5.8076888889,57.4014166667,457.20000000000005 -5.808275,57.4054472222,457.20000000000005 -5.8103805556,57.4064611111,457.20000000000005 -5.8136277778,57.4072611111,457.20000000000005 -5.8158,57.4105222222,457.20000000000005 -5.8187833333,57.4119611111,457.20000000000005 -5.8237111111,57.4112722222,457.20000000000005 -5.8244055556,57.4131388889,457.20000000000005 -5.8238833333,57.4161222222,457.20000000000005 -5.8244111111,57.4179944444,457.20000000000005 -5.8238777778,57.4192694444,457.20000000000005 -5.8217138889,57.4224833333,457.20000000000005 -5.8211166667,57.42475,457.20000000000005 -5.8184166667,57.4276194444,457.20000000000005 -5.8169944444,57.4283805556,457.20000000000005 -5.8152527778,57.4308611111,457.20000000000005 -5.8148944444,57.4322222222,457.20000000000005 -5.8130111111,57.4333583333,457.20000000000005 -5.8099277778,57.4341694444,457.20000000000005 -5.8050638889,57.4371055556,457.20000000000005 -5.8060277778,57.4399527778,457.20000000000005 -5.8101388889,57.4409972222,457.20000000000005 -5.8113777778,57.4416805556,457.20000000000005 -5.816375,57.4432361111,457.20000000000005 -5.8245111111,57.4412805556,457.20000000000005 -5.8296361111,57.4408555556,457.20000000000005 -5.8365972222,57.4404638889,457.20000000000005 -5.83995,57.4406305556,457.20000000000005 -5.8442444444,57.4402305556,457.20000000000005 -5.8498166667,57.4408694444,457.20000000000005 -5.8519055556,57.4417055556,457.20000000000005 -5.8557361111,57.444825,457.20000000000005 -5.8582361111,57.4479861111,457.20000000000005 -5.8597777778,57.4515361111,457.20000000000005 -5.8607666667,57.4545638889,457.20000000000005 -5.8599416667,57.457825,457.20000000000005 -5.8601833333,57.4616833333,457.20000000000005 -5.8628055556,57.4643916667,457.20000000000005 -5.8637527778,57.4670611111,457.20000000000005 -5.8619277778,57.4687333333,457.20000000000005 -5.8621166667,57.4705277778,457.20000000000005 -5.8678166667,57.4691833333,457.20000000000005 -5.8704361111,57.4702722222,457.20000000000005 -5.8712805556,57.4751027778,457.20000000000005 -5.8674472222,57.4798944444,457.20000000000005 -5.8674805556,57.4849305556,457.20000000000005 -5.86865,57.4896611111,457.20000000000005 -5.8662416667,57.4921611111,457.20000000000005 -5.8660944444,57.4954944444,457.20000000000005 -5.8653222222,57.497675,457.20000000000005 -5.8675888889,57.5017416667,457.20000000000005 -5.8654861111,57.5071111111,457.20000000000005 -5.8640333333,57.5076055556,457.20000000000005 -5.8626361111,57.5101666667,457.20000000000005 -5.8615805556,57.514425,457.20000000000005 -5.8604861111,57.5167083333,457.20000000000005 -5.8572277778,57.520675,457.20000000000005 -5.8556333333,57.5229694444,457.20000000000005 -5.8530027778,57.5265583333,457.20000000000005 -5.8536611111,57.5312138889,457.20000000000005 -5.853575,57.5335555556,457.20000000000005 -5.8515055556,57.5392833333,457.20000000000005 -5.8521333333,57.54205,457.20000000000005 -5.8519972222,57.5439444444,457.20000000000005 -5.8527805556,57.5497638889,457.20000000000005 -5.8457,57.5524083333,457.20000000000005 -5.8444638889,57.5549638889,457.20000000000005 -5.8476583333,57.5582833333,457.20000000000005 -5.8486388889,57.5612222222,457.20000000000005 -5.8474555556,57.5626972222,457.20000000000005 -5.8447194444,57.56215,457.20000000000005 -5.8395916667,57.5595194444,457.20000000000005 -5.8376305556,57.5567916667,457.20000000000005 -5.8345305556,57.5591333333,457.20000000000005 -5.8343666667,57.5607555556,457.20000000000005 -5.8356972222,57.5638638889,457.20000000000005 -5.8353916667,57.5689083333,457.20000000000005 -5.8387138889,57.5702444444,457.20000000000005 -5.8395444444,57.5733666667,457.20000000000005 -5.8410444444,57.5764694444,457.20000000000005 -5.8387083333,57.5765416667,457.20000000000005 -5.8361222222,57.5774277778,457.20000000000005 -5.8333333333,57.5791666667,457.20000000000005 -5.8333333333,57.6333333333,457.20000000000005 -5.9666666667,57.6333333333,457.20000000000005 -5.9666666667,57.5833333333,457.20000000000005 -5.9656777778,57.5819638889,457.20000000000005 -5.9642555556,57.5796722222,457.20000000000005 -5.960025,57.5807944444,457.20000000000005 -5.9598694444,57.5793611111,457.20000000000005 -5.9559944444,57.5791222222,457.20000000000005 -5.9558777778,57.5780472222,457.20000000000005 -5.9564777778,57.5758694444,457.20000000000005 -5.9558805556,57.5734611111,457.20000000000005 -5.9561,57.5693166667,457.20000000000005 -5.9538444444,57.5685777778,457.20000000000005 -5.9538555556,57.5656111111,457.20000000000005 -5.9564277778,57.5646305556,457.20000000000005 -5.9579111111,57.562875,457.20000000000005 -5.9565777778,57.5613888889,457.20000000000005 -5.9577166667,57.5595527778,457.20000000000005 -5.9601694444,57.5574972222,457.20000000000005 -5.9604083333,57.5550638889,457.20000000000005 -5.9609583333,57.5524388889,457.20000000000005 -5.9635583333,57.5517277778,457.20000000000005 -5.9653055556,57.5493333333,457.20000000000005 -5.9653555556,57.546725,457.20000000000005 -5.9635722222,57.5441722222,457.20000000000005 -5.9645444444,57.5423444444,457.20000000000005 -5.9657694444,57.5413166667,457.20000000000005 -5.9664888889,57.5386861111,457.20000000000005 -5.9691638889,57.5371611111,457.20000000000005 -5.968675,57.5342111111,457.20000000000005 -5.9699222222,57.5318333333,457.20000000000005 -5.9722833333,57.5305,457.20000000000005 -5.9700305556,57.5282333333,457.20000000000005 -5.9688472222,57.5265611111,457.20000000000005 -5.9705138889,57.5249805556,457.20000000000005 -5.9723861111,57.5237527778,457.20000000000005 -5.9724361111,57.5226694444,457.20000000000005 -5.9715555556,57.5207194444,457.20000000000005 -5.9743277778,57.5185638889,457.20000000000005 -5.9744472222,57.5165833333,457.20000000000005 -5.9756527778,57.515375,457.20000000000005 -5.9758777778,57.51285,457.20000000000005 -5.9765055556,57.5109416667,457.20000000000005 -5.9816888889,57.5094305556,457.20000000000005 -5.9858027778,57.50885,457.20000000000005 -5.9897583333,57.5053083333,457.20000000000005 -5.9887194444,57.5034527778,457.20000000000005 -5.9866527778,57.5028861111,457.20000000000005 -5.9850777778,57.5006888889,457.20000000000005 -5.9834805556,57.4998388889,457.20000000000005 -5.983375,57.497325,457.20000000000005 -5.9801138889,57.495,457.20000000000005 -5.9782555556,57.4932611111,457.20000000000005 -5.9807222222,57.4913833333,457.20000000000005 -5.9810944444,57.4902027778,457.20000000000005 -5.9808805556,57.4882305556,457.20000000000005 -5.9821027778,57.485675,457.20000000000005 -5.9831527778,57.4845638889,457.20000000000005 -5.9831722222,57.4816833333,457.20000000000005 -5.9837888889,57.4796861111,457.20000000000005 -5.9864222222,57.4778055556,457.20000000000005 -5.9860888889,57.4762861111,457.20000000000005 -5.987175,57.4740027778,457.20000000000005 -5.99015,57.4706722222,457.20000000000005 -5.9904444444,57.468775,457.20000000000005 -5.9925472222,57.4651111111,457.20000000000005 -5.9954416667,57.4610611111,457.20000000000005 -5.9973111111,57.4583055556,457.20000000000005 -5.9993361111,57.4569805556,457.20000000000005 -5.9996277778,57.4550833333,457.20000000000005 -6.0013388889,57.45395,457.20000000000005 -6.0022861111,57.4519416667,457.20000000000005 -6.004125,57.4504444444,457.20000000000005 -6.0071361111,57.4505277778,457.20000000000005 -6.0090527778,57.4497472222,457.20000000000005 -6.0092,57.4480333333,457.20000000000005 -6.0119472222,57.4472277778,457.20000000000005 -6.0136555556,57.4445638889,457.20000000000005 -6.02005,57.4435527778,457.20000000000005 -6.0248194444,57.4414222222,457.20000000000005 -6.0272611111,57.4378361111,457.20000000000005 -6.0312361111,57.4345611111,457.20000000000005 -6.0318694444,57.4327416667,457.20000000000005 -6.0310027778,57.4279138889,457.20000000000005 -6.0259861111,57.4232166667,457.20000000000005 -6.0235111111,57.4188888889,457.20000000000005 -6.0220611111,57.4163277778,457.20000000000005 -6.0200472222,57.4116277778,457.20000000000005 -6.0197805556,57.4092083333,457.20000000000005 -6.0189972222,57.406625,457.20000000000005 -6.01925,57.4043666667,457.20000000000005 -6.0186805556,57.4007,457.20000000000005 -6.0175166667,57.3976777778,457.20000000000005 -6.0179166667,57.3952388889,457.20000000000005 -6.0181277778,57.3895638889,457.20000000000005 -6.01465,57.3851805556,457.20000000000005 -6.0129305556,57.3831666667,457.20000000000005 -6.0101944444,57.3794777778,457.20000000000005 -6.0056472222,57.3759333333,457.20000000000005 -6.0029222222,57.3738638889,457.20000000000005 -6.0011083333,57.3709527778,457.20000000000005 -5.9974583333,57.3695388889,457.20000000000005 -5.9949305556,57.3707888889,457.20000000000005 -5.9935638889,57.3704722222,457.20000000000005 -5.9927944444,57.3679805556,457.20000000000005 -5.9930555556,57.3666666667,457.20000000000005 -5.8241666667,57.3666666667,457.20000000000005 + + + + + + EGD712A NORTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1654" txt_name="NORTHERN COMPLEX"><tr><td>585202N 0052659W -<br/>581310N 0052344W -<br/>581920N 0055243W -<br/>584432N 0055510W -<br/>585202N 0052659W <br/>Upper limit: FL660<br/>Lower limit: FL245<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -5.4496722222,58.8673305556,20116.8 -5.9194527778,58.7421972222,20116.8 -5.8786277778,58.3221666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 + + + + + relativeToGround + + + relativeToGround + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.9194527778,58.7421972222,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.8786277778,58.3221666667,20116.8 -5.9194527778,58.7421972222,20116.8 -5.9194527778,58.7421972222,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.8786277778,58.3221666667,20116.8 -5.8786277778,58.3221666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + + + EGD712B NORTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="952" txt_name="NORTHERN COMPLEX"><tr><td>591444N 0035801W -<br/>590716N 0033308W -<br/>580412N 0044247W -<br/>581310N 0052344W -<br/>585202N 0052659W -<br/>591444N 0035801W <br/>Upper limit: FL660<br/>Lower limit: FL245<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -3.9668944444,59.2454388889,20116.8 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.9668944444,59.2454388889,20116.8 + + + + + relativeToGround + + + relativeToGround + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 + + + + + relativeToGround + + + relativeToGround + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -3.9668944444,59.2454388889,20116.8 -3.9668944444,59.2454388889,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + relativeToGround + + + relativeToGround + -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 -3.9668944444,59.2454388889,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + + + EGD712C NORTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1655" txt_name="NORTHERN COMPLEX"><tr><td>590716N 0033308W -<br/>584654N 0022720W -<br/>574827N 0033350W -<br/>580412N 0044247W -<br/>590716N 0033308W <br/>Upper limit: FL660<br/>Lower limit: FL245<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -3.552325,59.1212277778,20116.8 + + + + + relativeToGround + + + relativeToGround + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 + + + + + relativeToGround + + + relativeToGround + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + relativeToGround + + + relativeToGround + -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + + + EGD712D NORTHERN COMPLEX + <table border="1" cellpadding="1" cellspacing="0" row_id="1656" txt_name="NORTHERN COMPLEX"><tr><td>584654N 0022720W -<br/>583622N 0015427W -<br/>574000N 0020624W following the line of latitude to -<br/>574000N 0025821W -<br/>574827N 0033350W -<br/>584654N 0022720W <br/>Upper limit: FL660<br/>Lower limit: FL245<br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: High Energy Manoeuvres.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -2.9724805556,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.1065472222,57.6666666667,20116.8 -1.907375,58.6059777778,20116.8 -2.4555083333,58.7817138889,20116.8 + + + + + relativeToGround + + + relativeToGround + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -2.9724805556,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + relativeToGround + + + relativeToGround + -3.5638888889,57.8074444444,7467.6 -2.9724805556,57.6666666667,7467.6 -2.9724805556,57.6666666667,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.9724805556,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.8281583333,57.6666666667,20116.8 -2.9724805556,57.6666666667,20116.8 -2.9724805556,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.6838361111,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.8281583333,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.5395138889,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.6838361111,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.3951916667,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.5395138889,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.2508694444,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.3951916667,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -2.1065472222,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.2508694444,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -1.907375,58.6059777778,20116.8 -2.1065472222,57.6666666667,20116.8 -2.1065472222,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -1.907375,58.6059777778,20116.8 -1.907375,58.6059777778,7467.6 + + + + + + + EGD713 FAST JET AREA SOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="12945" txt_name="FAST JET AREA SOUTH"><tr><td>575900N 0065200W -<br/>574600N 0061000W -<br/>563500N 0052200W -<br/>560600N 0063000W -<br/>561000N 0065400W -<br/>564200N 0081500W -<br/>575000N 0081500W -<br/>575900N 0065200W <br/>Upper limit: FL550<br/>Lower limit: FL245<br/>Class: </td><td>AMC: Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.<br/><br/>Danger Area Authority: HQ Air.<br/><br/>EGD713 is solely in support of Ex Joint Warrior.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -6.8666666667,57.9833333333,16764.0 -8.25,57.8333333333,16764.0 -8.25,56.7,16764.0 -6.9,56.1666666667,16764.0 -6.5,56.1,16764.0 -5.3666666667,56.5833333333,16764.0 -6.1666666667,57.7666666667,16764.0 -6.8666666667,57.9833333333,16764.0 + + + + + relativeToGround + + + relativeToGround + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.5,56.1,7467.6 -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 + + + + + relativeToGround + + + relativeToGround + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,57.8333333333,16764.0 -6.8666666667,57.9833333333,16764.0 -6.8666666667,57.9833333333,7467.6 + + + + + relativeToGround + + + relativeToGround + -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -8.25,56.7,16764.0 -8.25,57.8333333333,16764.0 -8.25,57.8333333333,7467.6 + + + + + relativeToGround + + + relativeToGround + -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.9,56.1666666667,16764.0 -8.25,56.7,16764.0 -8.25,56.7,7467.6 + + + + + relativeToGround + + + relativeToGround + -6.9,56.1666666667,7467.6 -6.5,56.1,7467.6 -6.5,56.1,16764.0 -6.9,56.1666666667,16764.0 -6.9,56.1666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -6.5,56.1,7467.6 -5.3666666667,56.5833333333,7467.6 -5.3666666667,56.5833333333,16764.0 -6.5,56.1,16764.0 -6.5,56.1,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.1666666667,57.7666666667,16764.0 -5.3666666667,56.5833333333,16764.0 -5.3666666667,56.5833333333,7467.6 + + + + + relativeToGround + + + relativeToGround + -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 -6.8666666667,57.9833333333,16764.0 -6.1666666667,57.7666666667,16764.0 -6.1666666667,57.7666666667,7467.6 + + + + + + + EGD801 CAPE WRATH (NORTH WEST) + <table border="1" cellpadding="1" cellspacing="0" row_id="953" txt_name="CAPE WRATH (NORTH WEST)"><tr><td>590000N 0043000W -<br/>584500N 0043000W following the line of latitude to -<br/>584500N 0050000W -<br/>590000N 0050000W following the line of latitude to -<br/>590000N 0043000W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.<br/><br/>Remarks: SI 1933/40.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5,59.0,16764.0 -4.6666666667,59.0,16764.0 -4.8333333333,59.0,16764.0 -5.0,59.0,16764.0 -5.0,58.75,16764.0 -4.8333333333,58.75,16764.0 -4.6666666667,58.75,16764.0 -4.5,58.75,16764.0 -4.5,59.0,16764.0 + + + + + + EGD802 CAPE WRATH (SOUTH EAST) + <table border="1" cellpadding="1" cellspacing="0" row_id="954" txt_name="CAPE WRATH (SOUTH EAST)"><tr><td>584500N 0043000W -<br/>583435N 0043000W - then along the coastline to<br/>583200N 0044728W -<br/>583200N 0050000W -<br/>584500N 0050000W -<br/>584500N 0043000W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.<br/><br/>Remarks: SI 1933/40.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5,58.75,16764.0 -5.0,58.75,16764.0 -5.0,58.5333333333,16764.0 -4.7911111111,58.5333333333,16764.0 -4.7888388889,58.5339416667,16764.0 -4.7865,58.5369583333,16764.0 -4.7850277778,58.5378888889,16764.0 -4.7821583333,58.5385805556,16764.0 -4.7800055556,58.5417722222,16764.0 -4.7775861111,58.5459583333,16764.0 -4.7768333333,58.5516388889,16764.0 -4.7810527778,58.5528055556,16764.0 -4.7883194444,58.5533666667,16764.0 -4.7911638889,58.5545611111,16764.0 -4.7964083333,58.5577722222,16764.0 -4.7979111111,58.5593583333,16764.0 -4.8025111111,58.5609666667,16764.0 -4.8052416667,58.5628833333,16764.0 -4.8051638889,58.5640527778,16764.0 -4.8023027778,58.5669916667,16764.0 -4.7998861111,58.5690222222,16764.0 -4.7968361111,58.5717833333,16764.0 -4.7967944444,58.5734027778,16764.0 -4.7955055556,58.5766666667,16764.0 -4.7934305556,58.5765305556,16764.0 -4.7921222222,58.5773694444,16764.0 -4.7896722222,58.5768833333,16764.0 -4.7874611111,58.5772,16764.0 -4.7850138889,58.5767138889,16764.0 -4.7835194444,58.577375,16764.0 -4.7754583333,58.5777305556,16764.0 -4.7714388889,58.5769166667,16764.0 -4.7660694444,58.5764944444,16764.0 -4.7634555556,58.5804138889,16764.0 -4.7632,58.5837444444,16764.0 -4.7669722222,58.5857305556,16764.0 -4.7716444444,58.5903944444,16764.0 -4.7741055556,58.5910583333,16764.0 -4.7765527778,58.5937027778,16764.0 -4.7847944444,58.5955916667,16764.0 -4.7883027778,58.5985694444,16764.0 -4.7902638889,58.5994277778,16764.0 -4.7905138889,58.6004083333,16764.0 -4.7868416667,58.5996805556,16764.0 -4.7832805556,58.6003861111,16764.0 -4.7772444444,58.6002472222,16764.0 -4.7743861111,58.603275,16764.0 -4.7684472222,58.6043916667,16764.0 -4.7687055556,58.6033083333,16764.0 -4.7699444444,58.601575,16764.0 -4.7695083333,58.6004138889,16764.0 -4.7655805556,58.5986111111,16764.0 -4.7646277778,58.5974638889,16764.0 -4.7666861111,58.5951722222,16764.0 -4.7654555556,58.5926833333,16764.0 -4.7653222222,58.5909777778,16764.0 -4.7623583333,58.5883472222,16764.0 -4.7578777778,58.5882638889,16764.0 -4.7567666667,58.5894555556,16764.0 -4.7544055556,58.5878888889,16764.0 -4.7537694444,58.586375,16764.0 -4.7526916667,58.5836111111,16764.0 -4.7491583333,58.5824277778,16764.0 -4.7442472222,58.5834333333,16764.0 -4.741725,58.5842055556,16764.0 -4.7414416667,58.5827722222,16764.0 -4.7396111111,58.581375,16764.0 -4.7406972222,58.5776666667,16764.0 -4.7425333333,58.5747527778,16764.0 -4.7409388889,58.5741583333,16764.0 -4.7406472222,58.5726361111,16764.0 -4.7386916667,58.5696222222,16764.0 -4.7324305556,58.5665194444,16764.0 -4.729175,58.5666777778,16764.0 -4.7267027778,58.5680805556,16764.0 -4.7254333333,58.5694555556,16764.0 -4.7205027778,58.5701888889,16764.0 -4.7173277778,58.5691777778,16764.0 -4.7176888889,58.5671916667,16764.0 -4.7182972222,58.5639444444,16764.0 -4.7163972222,58.56605,16764.0 -4.7141944444,58.5687027778,16764.0 -4.7092666667,58.5672805556,16764.0 -4.7046722222,58.5656694444,16764.0 -4.70695,58.5640027778,16764.0 -4.7093138889,58.5634138889,16764.0 -4.7096194444,58.5607111111,16764.0 -4.704125,58.5585805556,16764.0 -4.7022972222,58.5571833333,16764.0 -4.6996666667,58.5565194444,16764.0 -4.6955333333,58.556425,16764.0 -4.6915916667,58.5565972222,16764.0 -4.6897777778,58.5553777778,16764.0 -4.6859944444,58.5553666667,16764.0 -4.6826361111,58.5541805556,16764.0 -4.6787833333,58.5532722222,16764.0 -4.6781583333,58.5518472222,16764.0 -4.6789222222,58.5505722222,16764.0 -4.6741638889,58.5490555556,16764.0 -4.6741,58.5504944444,16764.0 -4.6698444444,58.5510305556,16764.0 -4.6644805556,58.5506027778,16764.0 -4.6621944444,58.5521777778,16764.0 -4.6593666667,58.5511583333,16764.0 -4.65495,58.5518805556,16764.0 -4.6533166667,58.5507444444,16764.0 -4.6577416667,58.5478666667,16764.0 -4.6579833333,58.5465138889,16764.0 -4.6575111111,58.5448166667,16764.0 -4.6549027778,58.5444222222,16764.0 -4.6536194444,58.5433694444,16764.0 -4.6541222222,58.5409333333,16764.0 -4.6516722222,58.5403555556,16764.0 -4.6519083333,58.5389111111,16764.0 -4.6504388889,58.5376833333,16764.0 -4.6507305556,58.5347111111,16764.0 -4.6525638889,58.5339555556,16764.0 -4.6531222222,58.5322361111,16764.0 -4.6598416667,58.5279638889,16764.0 -4.6617027778,58.5253194444,16764.0 -4.6653138889,58.5253333333,16764.0 -4.6672888889,58.5264611111,16764.0 -4.6697861111,58.5254222222,16764.0 -4.6733083333,58.5220222222,16764.0 -4.6764222222,58.5200694444,16764.0 -4.6799694444,58.5170305556,16764.0 -4.6825277778,58.51455,16764.0 -4.6842916667,58.5128972222,16764.0 -4.6871722222,58.5123861111,16764.0 -4.6932972222,58.5093833333,16764.0 -4.6931583333,58.5053416667,16764.0 -4.6987944444,58.5027055556,16764.0 -4.7025694444,58.5004694444,16764.0 -4.7072583333,58.4989333333,16764.0 -4.7100555556,58.4973472222,16764.0 -4.7121166667,58.4951472222,16764.0 -4.7145194444,58.4906916667,16764.0 -4.7170527778,58.4879416667,16764.0 -4.71765,58.4867611111,16764.0 -4.7203805556,58.4843666667,16764.0 -4.7222277778,58.4816333333,16764.0 -4.7251944444,58.4800416667,16764.0 -4.7267472222,58.4779416667,16764.0 -4.7280861111,58.4753055556,16764.0 -4.7307222222,58.4739027778,16764.0 -4.7344666667,58.4713055556,16764.0 -4.7383333333,58.4680777778,16764.0 -4.7385833333,58.4669055556,16764.0 -4.7443222222,58.4628361111,16764.0 -4.7441861111,58.4611055556,16764.0 -4.7425361111,58.4581916667,16764.0 -4.7486472222,58.4595888889,16764.0 -4.7506277778,58.4564027778,16764.0 -4.7488222222,58.453025,16764.0 -4.7537166667,58.4507194444,16764.0 -4.7582972222,58.4492277778,16764.0 -4.7553166667,58.4483916667,16764.0 -4.7476916667,58.4495444444,16764.0 -4.7484138889,58.4478222222,16764.0 -4.7491083333,58.4457388889,16764.0 -4.7467416667,58.44615,16764.0 -4.7428833333,58.4472222222,16764.0 -4.7409277778,58.4485222222,16764.0 -4.7356666667,58.4470166667,16764.0 -4.7324972222,58.4481611111,16764.0 -4.7285888889,58.4530083333,16764.0 -4.7243194444,58.4576833333,16764.0 -4.7244527778,58.4593861111,16764.0 -4.7213472222,58.4635861111,16764.0 -4.7148,58.4631861111,16764.0 -4.7119722222,58.464325,16764.0 -4.7069027778,58.4653305556,16764.0 -4.7046027778,58.4666388889,16764.0 -4.6980888889,58.4689305556,16764.0 -4.694775,58.4726861111,16764.0 -4.6944527778,58.4752083333,16764.0 -4.6932833333,58.4778388889,16764.0 -4.6876361111,58.4780472222,16764.0 -4.6836555556,58.4775916667,16764.0 -4.6808611111,58.4791777778,16764.0 -4.6776333333,58.4818527778,16764.0 -4.6717666667,58.4836805556,16764.0 -4.6679,58.4825055556,16764.0 -4.6630916667,58.482425,16764.0 -4.661025,58.484625,16764.0 -4.6605111111,58.4868805556,16764.0 -4.6614888889,58.490725,16764.0 -4.6605,58.4935305556,16764.0 -4.660675,58.4958638889,16764.0 -4.6616055556,58.4968333333,16764.0 -4.6608916667,58.4987361111,16764.0 -4.6589833333,58.503,16764.0 -4.6583972222,58.5066055556,16764.0 -4.6556472222,58.5088194444,16764.0 -4.6511444444,58.5106194444,16764.0 -4.6507194444,58.5117972222,16764.0 -4.6481305556,58.5139166667,16764.0 -4.6474027778,58.5156388889,16764.0 -4.6442583333,58.5172333333,16764.0 -4.6433722222,58.5191388889,16764.0 -4.6405694444,58.5207222222,16764.0 -4.6376222222,58.5203333333,16764.0 -4.6324277778,58.5198111111,16764.0 -4.6274388889,58.5219805556,16764.0 -4.6224472222,58.52415,16764.0 -4.6163972222,58.5236444444,16764.0 -4.6169472222,58.5218361111,16764.0 -4.6151722222,58.5210638889,16764.0 -4.6144638889,58.5184722222,16764.0 -4.6153722222,58.5168361111,16764.0 -4.6153833333,58.5146777778,16764.0 -4.6192472222,58.5135222222,16764.0 -4.6205527778,58.5125972222,16764.0 -4.6184944444,58.5073277778,16764.0 -4.61745,58.5078083333,16764.0 -4.6179666667,58.5101333333,16764.0 -4.6177833333,58.5122944444,16764.0 -4.6135638889,58.5132777778,16764.0 -4.6115083333,58.5156555556,16764.0 -4.6108388889,58.5205222222,16764.0 -4.6076555556,58.5239138889,16764.0 -4.6025166667,58.5264444444,16764.0 -4.5996138889,58.5266805556,16764.0 -4.59945,58.5291111111,16764.0 -4.5989638889,58.5318166667,16764.0 -4.5949833333,58.5337833333,16764.0 -4.5909666667,58.5352138889,16764.0 -4.59195,58.5369,16764.0 -4.5906833333,58.5407,16764.0 -4.591675,58.5448138889,16764.0 -4.5941777778,58.54845,16764.0 -4.6008472222,58.5526277778,16764.0 -4.6020444444,58.55485,16764.0 -4.5994,58.5585861111,16764.0 -4.594725,58.5604805556,16764.0 -4.5946861111,58.5622777778,16764.0 -4.5930805556,58.5638361111,16764.0 -4.5935638889,58.5657138889,16764.0 -4.5960277778,58.566475,16764.0 -4.594225,58.5676777778,16764.0 -4.597375,58.5684222222,16764.0 -4.5973111111,58.5698638889,16764.0 -4.5962222222,58.5714111111,16764.0 -4.5939083333,58.5727166667,16764.0 -4.5908972222,58.5738555556,16764.0 -4.5868611111,58.5751055556,16764.0 -4.5901583333,58.5754888889,16764.0 -4.58805,58.5772388889,16764.0 -4.5841194444,58.5775861111,16764.0 -4.5809138889,58.5784611111,16764.0 -4.5794527778,58.5796583333,16764.0 -4.5767638889,58.5805194444,16764.0 -4.5751444444,58.5795638889,16764.0 -4.570575,58.5758833333,16764.0 -4.5684527778,58.5751166667,16764.0 -4.5652805556,58.5764361111,16764.0 -4.561925,58.5775833333,16764.0 -4.55375,58.5763972222,16764.0 -4.5515166667,58.5764416667,16764.0 -4.5434027778,58.5784,16764.0 -4.5442333333,58.5803611111,16764.0 -4.5396555556,58.5789222222,16764.0 -4.53655,58.5788055556,16764.0 -4.5354166667,58.5798166667,16764.0 -4.5332722222,58.5786888889,16764.0 -4.5269027778,58.5786361111,16764.0 -4.5256972222,58.5762333333,16764.0 -4.5235944444,58.5757361111,16764.0 -4.52175,58.5764,16764.0 -4.5173805556,58.5778333333,16764.0 -4.5143138889,58.5782527778,16764.0 -4.51075,58.576525,16764.0 -4.506925,58.5759722222,16764.0 -4.5025916667,58.5755166667,16764.0 -4.5,58.5763888889,16764.0 -4.5,58.75,16764.0 + + + + + + EGD803 GARVIE ISLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="955" txt_name="GARVIE ISLAND"><tr><td>A circle, 4 NM radius, centred at 583705N 0045220W <br/>Upper limit: 40000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.<br/><br/>Danger Area Authority: DIO.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.8722222222,58.6845611849,12192.0 -4.8815454206,58.6843834303,12192.0 -4.8908185925,58.6838511206,12192.0 -4.8999919843,58.6829671118,12192.0 -4.909016387,58.6817361468,12192.0 -4.9178434039,58.6801648294,12192.0 -4.9264257149,58.6782615883,12192.0 -4.9347173328,58.6760366312,12192.0 -4.9426738539,58.673501889,12192.0 -4.9502526977,58.6706709512,12192.0 -4.9574133368,58.6675589918,12192.0 -4.9641175159,58.6641826866,12192.0 -4.9703294558,58.6605601231,12192.0 -4.9760160454,58.6567107024,12192.0 -4.981147017,58.6526550338,12192.0 -4.9856951069,58.6484148234,12192.0 -4.9896361975,58.6440127571,12192.0 -4.9929494437,58.6394723782,12192.0 -4.9956173795,58.6348179603,12192.0 -4.9976260072,58.6300743768,12192.0 -4.9989648664,58.6252669678,12192.0 -4.9996270849,58.6204214036,12192.0 -4.9996094092,58.6155635479,12192.0 -4.9989122161,58.610719319,12192.0 -4.9975395044,58.6059145521,12192.0 -4.9954988679,58.6011748612,12192.0 -4.992801449,58.5965255033,12192.0 -4.9894618741,58.5919912442,12192.0 -4.98549817,58.587596227,12192.0 -4.9809316641,58.5833638446,12192.0 -4.9757868662,58.5793166162,12192.0 -4.9700913349,58.575476068,12192.0 -4.9638755284,58.5718626203,12192.0 -4.9571726403,58.5684954797,12192.0 -4.9500184221,58.5653925384,12192.0 -4.9424509926,58.5625702802,12192.0 -4.9345106356,58.560043694,12192.0 -4.9262395872,58.5578261953,12192.0 -4.9176818128,58.5559295563,12192.0 -4.9088827764,58.5543638439,12192.0 -4.8998892021,58.5531373672,12192.0 -4.8907488293,58.5522566345,12192.0 -4.8815101633,58.5517263187,12192.0 -4.8722222222,58.5515492336,12192.0 -4.8629342812,58.5517263187,12192.0 -4.8536956152,58.5522566345,12192.0 -4.8445552423,58.5531373672,12192.0 -4.835561668,58.5543638439,12192.0 -4.8267626317,58.5559295563,12192.0 -4.8182048573,58.5578261953,12192.0 -4.8099338088,58.560043694,12192.0 -4.8019934519,58.5625702802,12192.0 -4.7944260223,58.5653925384,12192.0 -4.7872718041,58.5684954797,12192.0 -4.780568916,58.5718626203,12192.0 -4.7743531095,58.575476068,12192.0 -4.7686575783,58.5793166162,12192.0 -4.7635127804,58.5833638446,12192.0 -4.7589462744,58.587596227,12192.0 -4.7549825704,58.5919912442,12192.0 -4.7516429954,58.5965255033,12192.0 -4.7489455766,58.6011748612,12192.0 -4.7469049401,58.6059145521,12192.0 -4.7455322283,58.610719319,12192.0 -4.7448350352,58.6155635479,12192.0 -4.7448173595,58.6204214036,12192.0 -4.745479578,58.6252669678,12192.0 -4.7468184373,58.6300743768,12192.0 -4.7488270649,58.6348179603,12192.0 -4.7514950008,58.6394723782,12192.0 -4.7548082469,58.6440127571,12192.0 -4.7587493376,58.6484148234,12192.0 -4.7632974274,58.6526550338,12192.0 -4.7684283991,58.6567107024,12192.0 -4.7741149886,58.6605601231,12192.0 -4.7803269286,58.6641826866,12192.0 -4.7870311076,58.6675589918,12192.0 -4.7941917468,58.6706709512,12192.0 -4.8017705905,58.673501889,12192.0 -4.8097271116,58.6760366312,12192.0 -4.8180187296,58.6782615883,12192.0 -4.8266010405,58.6801648294,12192.0 -4.8354280575,58.6817361468,12192.0 -4.8444524601,58.6829671118,12192.0 -4.853625852,58.6838511206,12192.0 -4.8628990238,58.6843834303,12192.0 -4.8722222222,58.6845611849,12192.0 + + + + + + EGD809C MORAY FIRTH (CENTRAL) + <table border="1" cellpadding="1" cellspacing="0" row_id="957" txt_name="MORAY FIRTH (CENTRAL)"><tr><td>585000N 0023314W following the line of latitude to -<br/>585000N 0014526W -<br/>582600N 0015049W following the line of latitude to -<br/>582600N 0024048W -<br/>585000N 0023314W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5538888889,58.8333333333,16764.0 -2.68,58.4333333333,16764.0 -2.5133888889,58.4333333333,16764.0 -2.3467777778,58.4333333333,16764.0 -2.1801666667,58.4333333333,16764.0 -2.0135555556,58.4333333333,16764.0 -1.8469444444,58.4333333333,16764.0 -1.7572222222,58.8333333333,16764.0 -1.9165555556,58.8333333333,16764.0 -2.0758888889,58.8333333333,16764.0 -2.2352222222,58.8333333333,16764.0 -2.3945555556,58.8333333333,16764.0 -2.5538888889,58.8333333333,16764.0 + + + + + + EGD809N MORAY FIRTH (NORTH) + <table border="1" cellpadding="1" cellspacing="0" row_id="956" txt_name="MORAY FIRTH (NORTH)"><tr><td>592300N 0015130W following the line of latitude to -<br/>592300N 0014200W -<br/>590500N 0014200W -<br/>585000N 0014526W following the line of latitude to -<br/>585000N 0023314W -<br/>585800N 0023040W -<br/>592300N 0015130W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8583333333,59.3833333333,16764.0 -2.5111111111,58.9666666667,16764.0 -2.5538888889,58.8333333333,16764.0 -2.3945555556,58.8333333333,16764.0 -2.2352222222,58.8333333333,16764.0 -2.0758888889,58.8333333333,16764.0 -1.9165555556,58.8333333333,16764.0 -1.7572222222,58.8333333333,16764.0 -1.7,59.0833333333,16764.0 -1.7,59.3833333333,16764.0 -1.8583333333,59.3833333333,16764.0 + + + + + + EGD809S MORAY FIRTH (SOUTH) + <table border="1" cellpadding="1" cellspacing="0" row_id="960" txt_name="MORAY FIRTH (SOUTH)"><tr><td>582600N 0024048W following the line of latitude to -<br/>582600N 0015049W -<br/>575000N 0015840W following the line of latitude to -<br/>575000N 0022415W -<br/>581630N 0024345W -<br/>582600N 0024048W <br/>Upper limit: 55000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>AMC - Manageable.<br/><br/>Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.<br/><br/>Service: SUAAIS: Scottish Information on 133.675 MHz.<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.<br/><br/>Danger Area Authority: HQ Air.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.68,58.4333333333,16764.0 -2.7291666667,58.275,16764.0 -2.4041666667,57.8333333333,16764.0 -2.262037037,57.8333333333,16764.0 -2.1199074074,57.8333333333,16764.0 -1.9777777778,57.8333333333,16764.0 -1.8469444444,58.4333333333,16764.0 -2.0135555556,58.4333333333,16764.0 -2.1801666667,58.4333333333,16764.0 -2.3467777778,58.4333333333,16764.0 -2.5133888889,58.4333333333,16764.0 -2.68,58.4333333333,16764.0 + + + + + + EGD901 FAST JET AREA NORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="12943" txt_name="FAST JET AREA NORTH"><tr><td>594000N 0013000W -<br/>591000N 0010000W -<br/>580215N 0000948E -<br/>574700N 0010000W -<br/>574000N 0013100W following the line of latitude to -<br/>574000N 0025821W -<br/>581920N 0055243W -<br/>595000N 0060149W -<br/>594000N 0013000W <br/>Upper limit: FL550<br/>Lower limit: FL245<br/>Class: </td><td>AMC: Manageable.<br/><br/>Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).<br/><br/>Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.<br/><br/>Danger Area Authority: HQ Air.<br/><br/>EGD901 is solely in support of Ex Joint Warrior.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -1.5,59.6666666667,16764.0 -6.0302777778,59.8333333333,16764.0 -5.8786111111,58.3222222222,16764.0 -2.9725,57.6666666667,16764.0 -2.8107407407,57.6666666667,16764.0 -2.6489814815,57.6666666667,16764.0 -2.4872222222,57.6666666667,16764.0 -2.325462963,57.6666666667,16764.0 -2.1637037037,57.6666666667,16764.0 -2.0019444444,57.6666666667,16764.0 -1.8401851852,57.6666666667,16764.0 -1.6784259259,57.6666666667,16764.0 -1.5166666667,57.6666666667,16764.0 -1.0,57.7833333333,16764.0 0.1633333333,58.0375,16764.0 -1.0,59.1666666667,16764.0 -1.5,59.6666666667,16764.0 + + + + + relativeToGround + + + relativeToGround + -1.5,59.6666666667,7467.6 -6.0302777778,59.8333333333,7467.6 -5.8786111111,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1.0,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 -1.0,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.5,59.6666666667,7467.6 -6.0302777778,59.8333333333,7467.6 -6.0302777778,59.8333333333,16764.0 -1.5,59.6666666667,16764.0 -1.5,59.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -6.0302777778,59.8333333333,7467.6 -5.8786111111,58.3222222222,7467.6 -5.8786111111,58.3222222222,16764.0 -6.0302777778,59.8333333333,16764.0 -6.0302777778,59.8333333333,7467.6 + + + + + relativeToGround + + + relativeToGround + -5.8786111111,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.9725,57.6666666667,16764.0 -5.8786111111,58.3222222222,16764.0 -5.8786111111,58.3222222222,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.8107407407,57.6666666667,16764.0 -2.9725,57.6666666667,16764.0 -2.9725,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.6489814815,57.6666666667,16764.0 -2.8107407407,57.6666666667,16764.0 -2.8107407407,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.4872222222,57.6666666667,16764.0 -2.6489814815,57.6666666667,16764.0 -2.6489814815,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.325462963,57.6666666667,16764.0 -2.4872222222,57.6666666667,16764.0 -2.4872222222,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.1637037037,57.6666666667,16764.0 -2.325462963,57.6666666667,16764.0 -2.325462963,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -2.0019444444,57.6666666667,16764.0 -2.1637037037,57.6666666667,16764.0 -2.1637037037,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.8401851852,57.6666666667,16764.0 -2.0019444444,57.6666666667,16764.0 -2.0019444444,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.6784259259,57.6666666667,16764.0 -1.8401851852,57.6666666667,16764.0 -1.8401851852,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1.5166666667,57.6666666667,16764.0 -1.6784259259,57.6666666667,16764.0 -1.6784259259,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.5166666667,57.6666666667,7467.6 -1.0,57.7833333333,7467.6 -1.0,57.7833333333,16764.0 -1.5166666667,57.6666666667,16764.0 -1.5166666667,57.6666666667,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.0,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 0.1633333333,58.0375,16764.0 -1.0,57.7833333333,16764.0 -1.0,57.7833333333,7467.6 + + + + + relativeToGround + + + relativeToGround + 0.1633333333,58.0375,7467.6 -1.0,59.1666666667,7467.6 -1.0,59.1666666667,16764.0 0.1633333333,58.0375,16764.0 0.1633333333,58.0375,7467.6 + + + + + relativeToGround + + + relativeToGround + -1.0,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 -1.5,59.6666666667,16764.0 -1.0,59.1666666667,16764.0 -1.0,59.1666666667,7467.6 + + + + + + + + Prohibited + + EGP611 COULPORT / FASLANE + <table border="1" cellpadding="1" cellspacing="0" row_id="962" txt_name="COULPORT / FASLANE"><tr><td>A circle, 2 NM radius, centred at 560331N 0045159W <br/>Upper limit: 2200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.8663888889,56.0918776254,670.5600000000001 -4.8725074402,56.0917011577,670.5600000000001 -4.878560967,56.0911736299,670.5600000000001 -4.8844851413,56.0903006481,670.5600000000001 -4.8902170197,56.089091489,670.5600000000001 -4.8956957176,56.0875590008,670.5600000000001 -4.9008630591,56.0857194653,670.5600000000001 -4.9056641986,56.0835924241,670.5600000000001 -4.9100482046,56.0812004696,670.5600000000001 -4.9139686016,56.0785690036,670.5600000000001 -4.9173838627,56.0757259658,670.5600000000001 -4.9202578484,56.0727015362,670.5600000000001 -4.9225601874,56.069527813,670.5600000000001 -4.9242665941,56.0662384706,670.5600000000001 -4.9253591212,56.0628684018,670.5600000000001 -4.9258263439,56.0594533465,670.5600000000001 -4.9256634744,56.056029512,670.5600000000001 -4.9248724057,56.0526331894,670.5600000000001 -4.9234616844,56.0493003688,670.5600000000001 -4.9214464135,56.0460663579,670.5600000000001 -4.9188480857,56.0429654094,670.5600000000001 -4.9156943503,56.0400303583,670.5600000000001 -4.9120187157,56.0372922762,670.5600000000001 -4.9078601907,56.0347801428,670.5600000000001 -4.9032628694,56.0325205412,670.5600000000001 -4.8982754627,56.0305373778,670.5600000000001 -4.8929507836,56.0288516311,670.5600000000001 -4.887345189,56.0274811305,670.5600000000001 -4.8815179867,56.02644037,670.5600000000001 -4.8755308106,56.0257403549,670.5600000000001 -4.8694469739,56.0253884872,670.5600000000001 -4.8633308039,56.0253884872,670.5600000000001 -4.8572469672,56.0257403549,670.5600000000001 -4.8512597911,56.02644037,670.5600000000001 -4.8454325887,56.0274811305,670.5600000000001 -4.8398269942,56.0288516311,670.5600000000001 -4.8345023151,56.0305373778,670.5600000000001 -4.8295149084,56.0325205412,670.5600000000001 -4.824917587,56.0347801428,670.5600000000001 -4.8207590621,56.0372922762,670.5600000000001 -4.8170834275,56.0400303583,670.5600000000001 -4.8139296921,56.0429654094,670.5600000000001 -4.8113313643,56.0460663579,670.5600000000001 -4.8093160933,56.0493003688,670.5600000000001 -4.8079053721,56.0526331894,670.5600000000001 -4.8071143034,56.056029512,670.5600000000001 -4.8069514339,56.0594533465,670.5600000000001 -4.8074186566,56.0628684018,670.5600000000001 -4.8085111837,56.0662384706,670.5600000000001 -4.8102175904,56.069527813,670.5600000000001 -4.8125199293,56.0727015362,670.5600000000001 -4.8153939151,56.0757259658,670.5600000000001 -4.8188091761,56.0785690036,670.5600000000001 -4.8227295731,56.0812004696,670.5600000000001 -4.8271135792,56.0835924241,670.5600000000001 -4.8319147186,56.0857194653,670.5600000000001 -4.8370820602,56.0875590008,670.5600000000001 -4.8425607581,56.089091489,670.5600000000001 -4.8482926365,56.0903006481,670.5600000000001 -4.8542168107,56.0911736299,670.5600000000001 -4.8602703376,56.0917011577,670.5600000000001 -4.8663888889,56.0918776254,670.5600000000001 + + + + + + EGP813 DOUNREAY + <table border="1" cellpadding="1" cellspacing="0" row_id="961" txt_name="DOUNREAY"><tr><td>A circle, 2 NM radius, centred at 583435N 0034434W <br/>Upper limit: 2100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.7427777778,58.609642007,640.08 -3.7493300434,58.609465595,640.08 -3.7558126572,58.6089382341,640.08 -3.7621567139,58.6080655301,640.08 -3.7682947936,58.6068567592,640.08 -3.7741616829,58.6053247684,640.08 -3.7796950733,58.6034858381,640.08 -3.7848362261,58.6013595079,640.08 -3.7895305989,58.5989683673,640.08 -3.7937284254,58.5963378139,640.08 -3.7973852435,58.5934957828,640.08 -3.8004623645,58.5904724474,640.08 -3.8029272805,58.5872998982,640.08 -3.8047540042,58.5840118007,640.08 -3.8059233382,58.5806430368,640.08 -3.8064230716,58.5772293343,640.08 -3.8062481016,58.5738068869,640.08 -3.8054004792,58.5704119707,640.08 -3.8038893795,58.5670805596,640.08 -3.8017309962,58.5638479444,640.08 -3.7989483623,58.56074836,640.08 -3.7955710999,58.5578146233,640.08 -3.7916351009,58.5550777877,640.08 -3.7871821421,58.5525668152,640.08 -3.7822594409,58.5503082721,640.08 -3.7769191536,58.5483260487,640.08 -3.7712178237,58.5466411091,640.08 -3.7652157856,58.5452712702,640.08 -3.7589765288,58.5442310155,640.08 -3.7525660311,58.5435313422,640.08 -3.7460520656,58.5431796467,640.08 -3.7395034899,58.5431796467,640.08 -3.7329895244,58.5435313422,640.08 -3.7265790268,58.5442310155,640.08 -3.72033977,58.5452712702,640.08 -3.7143377318,58.5466411091,640.08 -3.708636402,58.5483260487,640.08 -3.7032961146,58.5503082721,640.08 -3.6983734134,58.5525668152,640.08 -3.6939204547,58.5550777877,640.08 -3.6899844556,58.5578146233,640.08 -3.6866071933,58.56074836,640.08 -3.6838245594,58.5638479444,640.08 -3.681666176,58.5670805596,640.08 -3.6801550763,58.5704119707,640.08 -3.679307454,58.5738068869,640.08 -3.6791324839,58.5772293343,640.08 -3.6796322173,58.5806430368,640.08 -3.6808015513,58.5840118007,640.08 -3.682628275,58.5872998982,640.08 -3.6850931911,58.5904724474,640.08 -3.6881703121,58.5934957828,640.08 -3.6918271301,58.5963378139,640.08 -3.6960249567,58.5989683673,640.08 -3.7007193295,58.6013595079,640.08 -3.7058604823,58.6034858381,640.08 -3.7113938727,58.6053247684,640.08 -3.717260762,58.6068567592,640.08 -3.7233988416,58.6080655301,640.08 -3.7297428984,58.6089382341,640.08 -3.7362255122,58.609465595,640.08 -3.7427777778,58.609642007,640.08 + + + + + + + Restricted + + EGR002 DEVONPORT + <table border="1" cellpadding="1" cellspacing="0" row_id="1058" txt_name="DEVONPORT"><tr><td>A circle, 1 NM radius, centred at 502317N 0041114W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by helicopter for the purpose of landing or taking off from Kinterbury Point (KP) Helicopter Landing Site (HLS) and Ships within HM Naval Base with the permission of FOST / Plymouth Military Radar and in accordance with any conditions to which permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1872222222,50.4047047378,609.6 -4.1910152222,50.404527252,609.6 -4.1947272975,50.4039985814,609.6 -4.1982792553,50.403130005,609.6 -4.201595329,50.4019400528,609.6 -4.2046047982,50.4004541095,609.6 -4.2072435002,50.3987038712,609.6 -4.2094551986,50.3967266679,609.6 -4.2111927823,50.3945646657,609.6 -4.2124192668,50.3922639654,609.6 -4.2131085786,50.389873619,609.6 -4.2132461049,50.3874445819,609.6 -4.2128289986,50.3850286269,609.6 -4.211866232,50.38267724,609.6 -4.2103783981,50.3804405238,609.6 -4.2083972659,50.3783661309,609.6 -4.2059650983,50.3764982494,609.6 -4.203133748,50.3748766639,609.6 -4.1999635509,50.373535909,609.6 -4.1965220414,50.372504536,609.6 -4.1928825154,50.3718045064,609.6 -4.1891224728,50.3714507253,609.6 -4.1853219717,50.3714507253,609.6 -4.1815619291,50.3718045064,609.6 -4.177922403,50.372504536,609.6 -4.1744808935,50.373535909,609.6 -4.1713106965,50.3748766639,609.6 -4.1684793461,50.3764982494,609.6 -4.1660471786,50.3783661309,609.6 -4.1640660464,50.3804405238,609.6 -4.1625782125,50.38267724,609.6 -4.1616154458,50.3850286269,609.6 -4.1611983396,50.3874445819,609.6 -4.1613358658,50.389873619,609.6 -4.1620251776,50.3922639654,609.6 -4.1632516622,50.3945646657,609.6 -4.1649892459,50.3967266679,609.6 -4.1672009443,50.3987038712,609.6 -4.1698396462,50.4004541095,609.6 -4.1728491155,50.4019400528,609.6 -4.1761651891,50.403130005,609.6 -4.1797171469,50.4039985814,609.6 -4.1834292222,50.404527252,609.6 -4.1872222222,50.4047047378,609.6 + + + + + + EGR063 DUNGENESS + <table border="1" cellpadding="1" cellspacing="0" row_id="1156" txt_name="DUNGENESS"><tr><td>A circle, 2 NM radius, centred at 505449N 0005717E <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Dungeness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>Flight permitted by an aircraft which has taken off from or intends to land at London Ashford (Lydd) Airport flying in accordance with normal aviation practice which remains at least 1.5 NM from the position given at column 1 for Dungeness.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9547222222,50.9469064086,609.6 0.949303047,50.9467298142,609.6 0.9439414384,50.9462019069,609.6 0.9386943478,50.9453282944,609.6 0.9336175023,50.944118256,609.6 0.9287648099,50.9425846441,609.6 0.9241877838,50.9407437458,609.6 0.9199349935,50.9386151102,609.6 0.9160515477,50.9362213387,609.6 0.9125786149,50.9335878442,609.6 0.9095529867,50.9307425803,609.6 0.9070066893,50.9277157431,609.6 0.9049666453,50.9245394495,609.6 0.9034543919,50.921247396,609.6 0.9024858558,50.9178744997,609.6 0.9020711889,50.9144565275,609.6 0.9022146659,50.9110297167,609.6 0.9029146436,50.9076303902,609.6 0.9041635837,50.904294572,609.6 0.9059481378,50.9010576053,609.6 0.9082492935,50.897953779,609.6 0.9110425797,50.8950159648,609.6 0.9142983296,50.8922752704,609.6 0.9179819975,50.8897607111,609.6 0.9220545264,50.8874989035,609.6 0.9264727623,50.8855137854,609.6 0.9311899111,50.8838263633,609.6 0.9361560329,50.8824544915,609.6 0.9413185687,50.881412684,609.6 0.9466228939,50.8807119621,609.6 0.9520128933,50.8803597382,609.6 0.9574315512,50.8803597382,609.6 0.9628215506,50.8807119621,609.6 0.9681258757,50.881412684,609.6 0.9732884115,50.8824544915,609.6 0.9782545333,50.8838263633,609.6 0.9829716822,50.8855137854,609.6 0.9873899181,50.8874989035,609.6 0.9914624469,50.8897607111,609.6 0.9951461149,50.8922752704,609.6 0.9984018648,50.8950159648,609.6 1.001195151,50.897953779,609.6 1.0034963066,50.9010576053,609.6 1.0052808608,50.904294572,609.6 1.0065298009,50.9076303902,609.6 1.0072297785,50.9110297167,609.6 1.0073732555,50.9144565275,609.6 1.0069585887,50.9178744997,609.6 1.0059900525,50.921247396,609.6 1.0044777991,50.9245394495,609.6 1.0024377552,50.9277157431,609.6 0.9998914577,50.9307425803,609.6 0.9968658296,50.9335878442,609.6 0.9933928967,50.9362213387,609.6 0.9895094509,50.9386151102,609.6 0.9852566607,50.9407437458,609.6 0.9806796346,50.9425846441,609.6 0.9758269422,50.944118256,609.6 0.9707500967,50.9453282944,609.6 0.965503006,50.9462019069,609.6 0.9601413974,50.9467298142,609.6 0.9547222222,50.9469064086,609.6 + + + + + + EGR095 SARK + <table border="1" cellpadding="1" cellspacing="0" row_id="1111" txt_name="SARK"><tr><td>A circle, 3 NM radius, centred at 492546N 0022145W <br/>Upper limit: 2374 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight is not permitted except in conformity with any permission granted by or on behalf of the Channel Islands Director of Civil Aviation. The Island of Sark is within Bailiwick of Guernsey territorial waters although within the Brest FIR.<br/><br/>Guernsey SI 1985/21.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3625,49.4794001476,723.5952000000001 -2.3689155084,49.4792247688,723.5952000000001 -2.3752858801,49.4786998665,723.5952000000001 -2.3815662987,49.4778291334,723.5952000000001 -2.3877125865,49.4766186951,723.5952000000001 -2.3936815175,49.4750770665,723.5952000000001 -2.3994311242,49.4732150914,723.5952000000001 -2.4049209946,49.4710458655,723.5952000000001 -2.410112558,49.4685846435,723.5952000000001 -2.414969357,49.4658487315,723.5952000000001 -2.4194573051,49.4628573634,723.5952000000001 -2.4235449258,49.4596315661,723.5952000000001 -2.4272035732,49.4561940094,723.5952000000001 -2.4304076327,49.4525688468,723.5952000000001 -2.4331346987,49.4487815446,723.5952000000001 -2.4353657305,49.4448587019,723.5952000000001 -2.4370851827,49.4408278634,723.5952000000001 -2.4382811118,49.4367173255,723.5952000000001 -2.4389452565,49.4325559366,723.5952000000001 -2.439073092,49.4283728951,723.5952000000001 -2.4386638582,49.4241975438,723.5952000000001 -2.437720561,49.420059164,723.5952000000001 -2.4362499477,49.4159867707,723.5952000000001 -2.4342624555,49.412008909,723.5952000000001 -2.4317721356,49.4081534549,723.5952000000001 -2.4287965508,49.4044474198,723.5952000000001 -2.4253566504,49.4009167627,723.5952000000001 -2.4214766204,49.3975862086,723.5952000000001 -2.4171837129,49.3944790766,723.5952000000001 -2.4125080535,49.3916171169,723.5952000000001 -2.4074824296,49.3890203603,723.5952000000001 -2.4021420611,49.3867069782,723.5952000000001 -2.3965243537,49.3846931567,723.5952000000001 -2.3906686384,49.382992984,723.5952000000001 -2.3846158977,49.3816183531,723.5952000000001 -2.3784084803,49.3805788785,723.5952000000001 -2.3720898073,49.3798818303,723.5952000000001 -2.3657040712,49.3795320833,723.5952000000001 -2.3592959288,49.3795320833,723.5952000000001 -2.3529101927,49.3798818303,723.5952000000001 -2.3465915197,49.3805788785,723.5952000000001 -2.3403841023,49.3816183531,723.5952000000001 -2.3343313616,49.382992984,723.5952000000001 -2.3284756463,49.3846931567,723.5952000000001 -2.3228579389,49.3867069782,723.5952000000001 -2.3175175704,49.3890203603,723.5952000000001 -2.3124919465,49.3916171169,723.5952000000001 -2.3078162871,49.3944790766,723.5952000000001 -2.3035233796,49.3975862086,723.5952000000001 -2.2996433496,49.4009167627,723.5952000000001 -2.2962034492,49.4044474198,723.5952000000001 -2.2932278644,49.4081534549,723.5952000000001 -2.2907375445,49.412008909,723.5952000000001 -2.2887500523,49.4159867707,723.5952000000001 -2.287279439,49.420059164,723.5952000000001 -2.2863361418,49.4241975438,723.5952000000001 -2.285926908,49.4283728951,723.5952000000001 -2.2860547435,49.4325559366,723.5952000000001 -2.2867188882,49.4367173255,723.5952000000001 -2.2879148173,49.4408278634,723.5952000000001 -2.2896342695,49.4448587019,723.5952000000001 -2.2918653013,49.4487815446,723.5952000000001 -2.2945923673,49.4525688468,723.5952000000001 -2.2977964268,49.4561940094,723.5952000000001 -2.3014550742,49.4596315661,723.5952000000001 -2.3055426949,49.4628573634,723.5952000000001 -2.310030643,49.4658487315,723.5952000000001 -2.314887442,49.4685846435,723.5952000000001 -2.3200790054,49.4710458655,723.5952000000001 -2.3255688758,49.4732150914,723.5952000000001 -2.3313184825,49.4750770665,723.5952000000001 -2.3372874135,49.4766186951,723.5952000000001 -2.3434337013,49.4778291334,723.5952000000001 -2.3497141199,49.4786998665,723.5952000000001 -2.3560844916,49.4792247688,723.5952000000001 -2.3625,49.4794001476,723.5952000000001 + + + + + + EGR101 ALDERMASTON + <table border="1" cellpadding="1" cellspacing="0" row_id="1107" txt_name="ALDERMASTON"><tr><td>A circle, 1.5 NM radius, centred at 512203N 0010847W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Aldermaston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1463888889,51.3924695424,731.52 -1.1511093435,51.3922941889,731.52 -1.1557634263,51.391770594,731.52 -1.1602857032,51.3909061194,731.52 -1.164612602,51.3897129191,731.52 -1.16868331,51.3882077678,731.52 -1.1724406312,51.3864118238,731.52 -1.1758317931,51.3843503304,731.52 -1.1788091878,51.3820522599,731.52 -1.1813310418,51.3795499048,731.52 -1.1833620001,51.376878423,731.52 -1.1848736205,51.374075342,731.52 -1.1858447687,51.3711800313,731.52 -1.1862619106,51.3682331481,731.52 -1.1861192962,51.3652760659,731.52 -1.1854190348,51.3623502939,731.52 -1.1841710595,51.3594968935,731.52 -1.1823929815,51.3567559032,731.52 -1.1801098382,51.3541657774,731.52 -1.177353737,51.3517628473,731.52 -1.174163402,51.3495808134,731.52 -1.1705836278,51.3476502732,731.52 -1.1666646506,51.3459982944,731.52 -1.1624614438,51.3446480361,731.52 -1.1580329486,51.3436184261,731.52 -1.1534412499,51.342923896,731.52 -1.1487507096,51.3425741802,731.52 -1.1440270682,51.3425741802,731.52 -1.1393365279,51.342923896,731.52 -1.1347448292,51.3436184261,731.52 -1.130316334,51.3446480361,731.52 -1.1261131272,51.3459982944,731.52 -1.12219415,51.3476502732,731.52 -1.1186143758,51.3495808134,731.52 -1.1154240407,51.3517628473,731.52 -1.1126679396,51.3541657774,731.52 -1.1103847963,51.3567559032,731.52 -1.1086067183,51.3594968935,731.52 -1.1073587429,51.3623502939,731.52 -1.1066584816,51.3652760659,731.52 -1.1065158672,51.3682331481,731.52 -1.106933009,51.3711800313,731.52 -1.1079041573,51.374075342,731.52 -1.1094157777,51.376878423,731.52 -1.111446736,51.3795499048,731.52 -1.1139685899,51.3820522599,731.52 -1.1169459847,51.3843503304,731.52 -1.1203371465,51.3864118238,731.52 -1.1240944678,51.3882077678,731.52 -1.1281651757,51.3897129191,731.52 -1.1324920746,51.3909061194,731.52 -1.1370143515,51.391770594,731.52 -1.1416684343,51.3922941889,731.52 -1.1463888889,51.3924695424,731.52 + + + + + + EGR104 BURGHFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="1108" txt_name="BURGHFIELD"><tr><td>A circle, 1 NM radius, centred at 512424N 0010125W <br/>Upper limit: 2400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Burghfield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0236111111,51.4233129283,731.52 -1.0274878214,51.4231354714,731.52 -1.0312818179,51.4226068868,731.52 -1.0349121572,51.4217384523,731.52 -1.0383013983,51.4205486955,731.52 -1.0413772588,51.4190629976,731.52 -1.0440741597,51.4173130507,731.52 -1.0463346245,51.4153361794,731.52 -1.0481105042,51.4131745437,731.52 -1.0493640011,51.4108742375,731.52 -1.0500684699,51.4084843048,731.52 -1.0502089796,51.4060556927,731.52 -1.0497826245,51.403640165,731.52 -1.0487985788,51.4012891983,731.52 -1.0472778936,51.3990528858,731.52 -1.0452530415,51.3969788707,731.52 -1.0427672195,51.3951113324,731.52 -1.0398734246,51.3934900469,731.52 -1.0366333234,51.3921495417,731.52 -1.033115938,51.3911183617,731.52 -1.0293961781,51.3904184636,731.52 -1.0255532497,51.3900647491,731.52 -1.0216689725,51.3900647491,731.52 -1.0178260441,51.3904184636,731.52 -1.0141062843,51.3911183617,731.52 -1.0105888988,51.3921495417,731.52 -1.0073487976,51.3934900469,731.52 -1.0044550028,51.3951113324,731.52 -1.0019691807,51.3969788707,731.52 -0.9999443286,51.3990528858,731.52 -0.9984236434,51.4012891983,731.52 -0.9974395977,51.403640165,731.52 -0.9970132426,51.4060556927,731.52 -0.9971537523,51.4084843048,731.52 -0.9978582211,51.4108742375,731.52 -0.999111718,51.4131745437,731.52 -1.0008875977,51.4153361794,731.52 -1.0031480625,51.4173130507,731.52 -1.0058449634,51.4190629976,731.52 -1.008920824,51.4205486955,731.52 -1.012310065,51.4217384523,731.52 -1.0159404043,51.4226068868,731.52 -1.0197344008,51.4231354714,731.52 -1.0236111111,51.4233129283,731.52 + + + + + + EGR105 HIGHGROVE HOUSE + <table border="1" cellpadding="1" cellspacing="0" row_id="1060" txt_name="HIGHGROVE HOUSE"><tr><td>A circle, 1.5 NM radius, centred at 513720N 0021050W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of National Police Air Service;<br/>any aircraft flying in the service of the Helicopter Emergency Medical Service;<br/>any aircraft flying in the service of the Maritime and Coastguard Agency;<br/>any aircraft flying in the service of The King's Helicopter Flight;<br/>any aircraft flying in accordance with a permission issued by the Gloucestershire Constabulary Royalty Household Protection Group;<br/>any aircraft either operated by a member of the Royal Family, or landing in the grounds of Highgrove House at the invitation of the person in charge of the household there, provided that the Gloucestershire Constabulary Royalty Household Protection Group has been informed in advance of such intended flight or landing.<br/><br/>SI 907/2018.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1805555556,51.6471906741,609.6 -2.1853024165,51.6470153274,609.6 -2.1899825335,51.6464917528,609.6 -2.1945301052,51.6456273118,609.6 -2.1988812033,51.6444341583,609.6 -2.2029746741,51.6429290662,609.6 -2.2067530014,51.6411331935,609.6 -2.2101631173,51.6390717828,609.6 -2.2131571481,51.6367738055,609.6 -2.2156930867,51.6342715531,609.6 -2.2177353812,51.6316001822,609.6 -2.2192554313,51.6287972192,609.6 -2.2202319857,51.625902032,609.6 -2.2206514358,51.6229552762,609.6 -2.2205080007,51.6199983237,609.6 -2.219803803,51.6170726815,609.6 -2.2185488324,51.6142194095,609.6 -2.2167607997,51.6114785441,609.6 -2.2144648831,51.6088885376,609.6 -2.2116933704,51.6064857195,609.6 -2.2084852023,51.6043037882,609.6 -2.204885424,51.6023733396,609.6 -2.2009445523,51.6007214398,609.6 -2.1967178674,51.5993712465,609.6 -2.1922646389,51.5983416863,609.6 -2.1876472979,51.5976471898,609.6 -2.1829305648,51.5972974911,609.6 -2.1781805463,51.5972974911,609.6 -2.1734638132,51.5976471898,609.6 -2.1688464722,51.5983416863,609.6 -2.1643932438,51.5993712465,609.6 -2.1601665588,51.6007214398,609.6 -2.1562256871,51.6023733396,609.6 -2.1526259088,51.6043037882,609.6 -2.1494177407,51.6064857195,609.6 -2.146646228,51.6088885376,609.6 -2.1443503114,51.6114785441,609.6 -2.1425622788,51.6142194095,609.6 -2.1413073081,51.6170726815,609.6 -2.1406031104,51.6199983237,609.6 -2.1404596754,51.6229552762,609.6 -2.1408791254,51.625902032,609.6 -2.1418556798,51.6287972192,609.6 -2.1433757299,51.6316001822,609.6 -2.1454180245,51.6342715531,609.6 -2.147953963,51.6367738055,609.6 -2.1509479938,51.6390717828,609.6 -2.1543581097,51.6411331935,609.6 -2.1581364371,51.6429290662,609.6 -2.1622299078,51.6444341583,609.6 -2.1665810059,51.6456273118,609.6 -2.1711285777,51.6464917528,609.6 -2.1758086946,51.6470153274,609.6 -2.1805555556,51.6471906741,609.6 + + + + + + EGR106 RAYMILL HOUSE, LACOCK + <table border="1" cellpadding="1" cellspacing="0" row_id="8875" txt_name="RAYMILL HOUSE, LACOCK"><tr><td>A circle, 1 NM radius, centred at 512523N 0020646W <br/>Upper limit: 1600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of National Police Air Service;<br/>any aircraft flying in the service of the Helicopter Emergency Medical Services;<br/>any aircraft flying in the service of Maritime and Coastguard Agency;<br/>any aircraft flying in the service of The King's Helicopter Flight.<br/><br/>Flying in accordance with an agreed exemption issued by, or with the permission of, the Wiltshire Police Constabulary Royalty Protection Department.<br/><br/>SI 703/2021.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1127777778,51.4397017704,487.68 -2.1166558753,51.4395243139,487.68 -2.1204512294,51.4389957307,487.68 -2.1240828677,51.4381272985,487.68 -2.1274733213,51.4369375448,487.68 -2.1305502821,51.4354518509,487.68 -2.1332481474,51.4337019086,487.68 -2.1355094204,51.4317250426,487.68 -2.1372859347,51.4295634128,487.68 -2.1385398793,51.4272631129,487.68 -2.1392445993,51.4248731868,487.68 -2.1393851584,51.4224445816,487.68 -2.13895865,51.4200290607,487.68 -2.1379742516,51.4176781007,487.68 -2.136453022,51.4154417947,487.68 -2.1344274453,51.4133677857,487.68 -2.1319407342,51.4115002529,487.68 -2.1290459045,51.4098789722,487.68 -2.1258046448,51.408538471,487.68 -2.122286002,51.4075072941,487.68 -2.1185649125,51.4068073981,487.68 -2.1147206105,51.4064536847,487.68 -2.110834945,51.4064536847,487.68 -2.106990643,51.4068073981,487.68 -2.1032695536,51.4075072941,487.68 -2.0997509107,51.408538471,487.68 -2.096509651,51.4098789722,487.68 -2.0936148214,51.4115002529,487.68 -2.0911281102,51.4133677857,487.68 -2.0891025336,51.4154417947,487.68 -2.0875813039,51.4176781007,487.68 -2.0865969056,51.4200290607,487.68 -2.0861703972,51.4224445816,487.68 -2.0863109563,51.4248731868,487.68 -2.0870156763,51.4272631129,487.68 -2.0882696209,51.4295634128,487.68 -2.0900461352,51.4317250426,487.68 -2.0923074081,51.4337019086,487.68 -2.0950052735,51.4354518509,487.68 -2.0980822343,51.4369375448,487.68 -2.1014726879,51.4381272985,487.68 -2.1051043261,51.4389957307,487.68 -2.1088996802,51.4395243139,487.68 -2.1127777778,51.4397017704,487.68 + + + + + + EGR153 HINKLEY POINT + <table border="1" cellpadding="1" cellspacing="0" row_id="1106" txt_name="HINKLEY POINT"><tr><td>A circle, 2 NM radius, centred at 511233N 0030749W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hinkley Point, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>Flight permitted by a helicopter flying within the Bridgewater Bay Danger Area with the permission of the person in charge of that Area and in accordance with any conditions to which that permission is subject which remains at least 1 NM from the position given at column 1 for Hinkley Point.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1301805556,51.2423352721,609.6 -3.1356343719,51.2421586853,609.6 -3.1410302524,51.2416308009,609.6 -3.1463108803,51.2407572264,609.6 -3.1514201712,51.239547241,609.6 -3.1563038717,51.2380136966,609.6 -3.1609101384,51.2361728802,609.6 -3.1651900912,51.2340443402,609.6 -3.1690983329,51.2316506773,609.6 -3.1725934322,51.229017304,609.6 -3.1756383627,51.2261721727,609.6 -3.1782008946,51.2231454786,609.6 -3.1802539342,51.2199693375,609.6 -3.1817758082,51.2166774443,609.6 -3.1827504897,51.2133047149,609.6 -3.1831677634,51.2098869144,609.6 -3.1830233292,51.2064602785,609.6 -3.1823188426,51.2030611281,609.6 -3.1810618915,51.1997254852,609.6 -3.1792659112,51.1964886911,609.6 -3.1769500369,51.1933850325,609.6 -3.1741388969,51.190447379,609.6 -3.1708623484,51.1877068364,609.6 -3.167155158,51.1851924178,609.6 -3.1630566323,51.182930738,609.6 -3.1586102005,51.180945733,609.6 -3.153862955,51.1792584078,609.6 -3.1488651536,51.1778866152,609.6 -3.1436696898,51.1768448681,609.6 -3.1383315354,51.176144187,609.6 -3.1329071624,51.1757919837,609.6 -3.1274539487,51.1757919837,609.6 -3.1220295757,51.176144187,609.6 -3.1166914213,51.1768448681,609.6 -3.1114959575,51.1778866152,609.6 -3.1064981561,51.1792584078,609.6 -3.1017509106,51.180945733,609.6 -3.0973044788,51.182930738,609.6 -3.0932059531,51.1851924178,609.6 -3.0894987627,51.1877068364,609.6 -3.0862222142,51.190447379,609.6 -3.0834110742,51.1933850325,609.6 -3.0810951999,51.1964886911,609.6 -3.0792992196,51.1997254852,609.6 -3.0780422685,51.2030611281,609.6 -3.0773377819,51.2064602785,609.6 -3.0771933477,51.2098869144,609.6 -3.0776106214,51.2133047149,609.6 -3.0785853029,51.2166774443,609.6 -3.0801071769,51.2199693375,609.6 -3.0821602165,51.2231454786,609.6 -3.0847227484,51.2261721727,609.6 -3.0877676789,51.229017304,609.6 -3.0912627782,51.2316506773,609.6 -3.0951710199,51.2340443402,609.6 -3.0994509727,51.2361728802,609.6 -3.1040572394,51.2380136966,609.6 -3.1089409399,51.239547241,609.6 -3.1140502308,51.2407572264,609.6 -3.1193308587,51.2416308009,609.6 -3.1247267392,51.2421586853,609.6 -3.1301805556,51.2423352721,609.6 + + + + + + EGR154 OLDBURY + <table border="1" cellpadding="1" cellspacing="0" row_id="1061" txt_name="OLDBURY"><tr><td>A circle, 2 NM radius, centred at 513852N 0023415W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Oldbury, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5708638889,51.6811522104,609.6 -2.5763702602,51.6809756349,609.6 -2.5818181352,51.6804477843,609.6 -2.5871496433,51.6795742659,609.6 -2.5923081578,51.6783643587,609.6 -2.597238901,51.6768309141,609.6 -2.6018895292,51.6749902186,609.6 -2.6062106904,51.6728618197,609.6 -2.6101565501,51.6704683175,609.6 -2.613685278,51.6678351232,609.6 -2.6167594919,51.664990188,609.6 -2.6193466528,51.6619637055,609.6 -2.6214194077,51.6587877899,609.6 -2.6229558766,51.6554961341,609.6 -2.6239398805,51.6521236517,609.6 -2.6243611085,51.6487061056,609.6 -2.6242152215,51.6452797286,609.6 -2.6235038936,51.6418808392,609.6 -2.6222347885,51.6385454562,609.6 -2.6204214729,51.6353089179,609.6 -2.6180832685,51.6322055079,609.6 -2.6152450422,51.6292680929,609.6 -2.6119369398,51.6265277754,609.6 -2.6081940633,51.6240135655,609.6 -2.6040560978,51.6217520754,609.6 -2.5995668902,51.6197672383,609.6 -2.5947739853,51.6180800568,609.6 -2.5897281231,51.6167083818,609.6 -2.5844827046,51.6156667245,609.6 -2.5790932284,51.6149661039,609.6 -2.5736167077,51.6146139311,609.6 -2.5681110701,51.6146139311,609.6 -2.5626345494,51.6149661039,609.6 -2.5572450732,51.6156667245,609.6 -2.5519996547,51.6167083818,609.6 -2.5469537925,51.6180800568,609.6 -2.5421608876,51.6197672383,609.6 -2.53767168,51.6217520754,609.6 -2.5335337145,51.6240135655,609.6 -2.529790838,51.6265277754,609.6 -2.5264827356,51.6292680929,609.6 -2.5236445093,51.6322055079,609.6 -2.5213063049,51.6353089179,609.6 -2.5194929893,51.6385454562,609.6 -2.5182238841,51.6418808392,609.6 -2.5175125563,51.6452797286,609.6 -2.5173666693,51.6487061056,609.6 -2.5177878972,51.6521236517,609.6 -2.5187719012,51.6554961341,609.6 -2.5203083701,51.6587877899,609.6 -2.522381125,51.6619637055,609.6 -2.5249682859,51.664990188,609.6 -2.5280424998,51.6678351232,609.6 -2.5315712277,51.6704683175,609.6 -2.5355170874,51.6728618197,609.6 -2.5398382486,51.6749902186,609.6 -2.5444888768,51.6768309141,609.6 -2.54941962,51.6783643587,609.6 -2.5545781345,51.6795742659,609.6 -2.5599096425,51.6804477843,609.6 -2.5653575176,51.6809756349,609.6 -2.5708638889,51.6811522104,609.6 + + + + + + EGR155 BERKELEY + <table border="1" cellpadding="1" cellspacing="0" row_id="1062" txt_name="BERKELEY"><tr><td>A circle, 2 NM radius, centred at 514134N 0022936W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Berkeley, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4933,51.7260130658,609.6 -2.4988118196,51.7258364915,609.6 -2.504265085,51.7253086443,609.6 -2.5096018678,51.7244351316,609.6 -2.5147654852,51.7232252324,609.6 -2.5197011053,51.7216917979,609.6 -2.5243563324,51.7198511147,609.6 -2.5286817657,51.7177227303,609.6 -2.5326315251,51.7153292444,609.6 -2.5361637393,51.7126960683,609.6 -2.539240989,51.7098511531,609.6 -2.5418307031,51.7068246922,609.6 -2.5439055018,51.7036487996,609.6 -2.5454434837,51.700357168,609.6 -2.5464284541,51.6969847108,609.6 -2.5468500919,51.6935671906,609.6 -2.5467040542,51.6901408401,609.6 -2.5459920171,51.6867419773,609.6 -2.5447216519,51.6834066208,609.6 -2.5429065392,51.6801701086,609.6 -2.5405660198,51.6770667241,609.6 -2.5377249855,51.6741293334,609.6 -2.5344136119,51.6713890388,609.6 -2.5306670359,51.6688748503,609.6 -2.5265249817,51.6666133795,609.6 -2.5220313396,51.6646285596,609.6 -2.5172337012,51.6629413928,609.6 -2.5121828567,51.6615697298,609.6 -2.5069322595,51.6605280817,609.6 -2.5015374629,51.6598274673,609.6 -2.4960555361,51.6594752976,609.6 -2.4905444639,51.6594752976,609.6 -2.4850625371,51.6598274673,609.6 -2.4796677405,51.6605280817,609.6 -2.4744171433,51.6615697298,609.6 -2.4693662988,51.6629413928,609.6 -2.4645686604,51.6646285596,609.6 -2.4600750183,51.6666133795,609.6 -2.4559329641,51.6688748503,609.6 -2.4521863881,51.6713890388,609.6 -2.4488750145,51.6741293334,609.6 -2.4460339802,51.6770667241,609.6 -2.4436934608,51.6801701086,609.6 -2.4418783481,51.6834066208,609.6 -2.4406079829,51.6867419773,609.6 -2.4398959458,51.6901408401,609.6 -2.4397499081,51.6935671906,609.6 -2.4401715459,51.6969847108,609.6 -2.4411565163,51.700357168,609.6 -2.4426944982,51.7036487996,609.6 -2.4447692969,51.7068246922,609.6 -2.447359011,51.7098511531,609.6 -2.4504362607,51.7126960683,609.6 -2.4539684749,51.7153292444,609.6 -2.4579182343,51.7177227303,609.6 -2.4622436676,51.7198511147,609.6 -2.4668988947,51.7216917979,609.6 -2.4718345148,51.7232252324,609.6 -2.4769981322,51.7244351316,609.6 -2.482334915,51.7253086443,609.6 -2.4877881804,51.7258364915,609.6 -2.4933,51.7260130658,609.6 + + + + + + EGR156 WINDSOR CASTLE + <table border="1" cellpadding="1" cellspacing="0" row_id="9474" txt_name="WINDSOR CASTLE"><tr><td>A circle, 1.25 NM radius, centred at 512902N 0003614W <br/>Upper limit: 2500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft operating for or on behalf of National Police Air Service;<br/>any aircraft operating for or on behalf of The Helicopter Emergency Medical Service;<br/>any aircraft operating for or on behalf of The Maritime and Coastguard Agency for the purposes of search and rescue operations;<br/>any aircraft operating for or on behalf of The King's Helicopter Flight;<br/>any aircraft operated by a member of the Royal Family;<br/>any aircraft flying in accordance with an agreed exemption issued by, or with the permission of, the Metropolitan Police (Royalty and Special Protection);<br/>or landing in the grounds of Windsor Great Park at the invitation of the Director of Royal Travel provided that Protective Security Operations (PSO) has been informed in advance of such intended flight or landing;<br/>any aircraft approaching to, or departing from, London Heathrow Airport.<br/><br/>SI 1137/2021.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6038888889,51.5046964329,762.0 -0.6082407864,51.504518341,762.0 -0.6125181214,51.5039871169,762.0 -0.6166476141,51.5031118618,762.0 -0.6205585275,51.5019075706,762.0 -0.6241838831,51.5003948741,762.0 -0.6274616116,51.4985996837,762.0 -0.630335617,51.4965527468,762.0 -0.6327567375,51.4942891181,762.0 -0.634683586,51.4918475578,762.0 -0.6360832551,51.4892698664,762.0 -0.6369318764,51.4866001681,762.0 -0.6372150232,51.4838841541,762.0 -0.6369279509,51.4811683001,762.0 -0.6360756717,51.4784990711,762.0 -0.6346728614,51.4759221263,762.0 -0.6327436027,51.4734815389,762.0 -0.630320967,51.4712190432,762.0 -0.6274464448,51.4691733222,762.0 -0.6241692331,51.4673793477,762.0 -0.6205453926,51.4658677841,762.0 -0.6166368896,51.4646644659,762.0 -0.612510538,51.4637899573,762.0 -0.6082368609,51.4632592024,762.0 -0.6038888889,51.4630812707,762.0 -0.5995409168,51.4632592024,762.0 -0.5952672398,51.4637899573,762.0 -0.5911408882,51.4646644659,762.0 -0.5872323852,51.4658677841,762.0 -0.5836085447,51.4673793477,762.0 -0.580331333,51.4691733222,762.0 -0.5774568108,51.4712190432,762.0 -0.5750341751,51.4734815389,762.0 -0.5731049163,51.4759221263,762.0 -0.5717021061,51.4784990711,762.0 -0.5708498268,51.4811683001,762.0 -0.5705627546,51.4838841541,762.0 -0.5708459014,51.4866001681,762.0 -0.5716945227,51.4892698664,762.0 -0.5730941918,51.4918475578,762.0 -0.5750210402,51.4942891181,762.0 -0.5774421608,51.4965527468,762.0 -0.5803161661,51.4985996837,762.0 -0.5835938946,51.5003948741,762.0 -0.5872192503,51.5019075706,762.0 -0.5911301637,51.5031118618,762.0 -0.5952596563,51.5039871169,762.0 -0.5995369914,51.504518341,762.0 -0.6038888889,51.5046964329,762.0 + + + + + + EGR157 HYDE PARK + <table border="1" cellpadding="1" cellspacing="0" row_id="1245" txt_name="HYDE PARK"><tr><td>513212N 0000911W -<br/>513020N 0000648W thence clockwise by the arc of a circle radius 0.55 NM centred on 513000N 0000730W to<br/>513001N 0000637W -<br/>512917N 0000634W thence clockwise by the arc of a circle radius 0.55 NM centred on 512915N 0000726W to<br/>512852N 0000649W -<br/>512834N 0000719W thence clockwise by the arc of a circle radius 0.55 NM centred on 512857N 0000756W to<br/>512858N 0000849W -<br/>512921N 0000847W -<br/>512939N 0001132W thence clockwise by the arc of a circle radius 0.55 NM centred on 513011N 0001123W to<br/>513028N 0001209W -<br/>513208N 0001038W thence clockwise by the arc of a circle radius 0.55 NM centred on 513151N 0000952W to -<br/>513212N 0000911W <br/>Upper limit: 1400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;<br/>any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;<br/>any helicopter flying on Helicopter Route H4;<br/>any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.<br/><br/>See also ENR 1.1, paragraph 4.1.6.<br/><br/>SI 1300/2017<br/><br/>Contact: www.nats.co.uk/nsf</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1529333333,51.5366111111,426.72 -0.1549267573,51.5378940871,426.72 -0.1572818369,51.5389111961,426.72 -0.1599088899,51.5396236997,426.72 -0.1627078613,51.5400044583,426.72 -0.1655721364,51.5400389683,426.72 -0.1683926087,51.5397259152,426.72 -0.1710618431,51.5390772237,426.72 -0.1734781752,51.5381176028,426.72 -0.1755495885,51.5368836029,426.72 -0.1771972222,51.5354222222,426.72 -0.2023722222,51.5076638889,426.72 -0.2035115549,51.5060699613,426.72 -0.2041447262,51.5043699176,426.72 -0.2042494731,51.5026257804,426.72 -0.2038220493,51.5009009245,426.72 -0.2028780428,51.4992580171,426.72 -0.2014518003,51.4977567415,426.72 -0.1995951734,51.4964516304,426.72 -0.1973756297,51.4953900866,426.72 -0.1948738011,51.4946106635,426.72 -0.1921805556,51.4941416667,426.72 -0.1464694444,51.4890388889,426.72 -0.1468722222,51.482875,426.72 -0.1467340709,51.4811955082,426.72 -0.1461068208,51.4795600798,426.72 -0.1450111174,51.4780238809,426.72 -0.1434839716,51.4766387391,426.72 -0.141576937,51.4754513811,426.72 -0.1393543671,51.4745018581,426.72 -0.1368912443,51.473822197,426.72 -0.1342706517,51.4734353207,426.72 -0.1315809745,51.4733542773,426.72 -0.1289129236,51.4735818,426.72 -0.1263564821,51.4741102153,426.72 -0.1239978753,51.4749217016,426.72 -0.1219166667,51.4759888889,426.72 -0.1136111111,51.4811111111,426.72 -0.1120090522,51.482252708,426.72 -0.1107683543,51.483560414,426.72 -0.109891236,51.4849782611,426.72 -0.1094019057,51.4864671731,426.72 -0.1093138889,51.4879861111,426.72 -0.1102416667,51.5003194444,426.72 -0.1105268172,51.5017362939,426.72 -0.1111609871,51.5031083023,426.72 -0.1121293381,51.504402069,426.72 -0.1134083333,51.5055861111,426.72 -0.1529333333,51.5366111111,426.72 + + + + + + EGR158 CITY OF LONDON + <table border="1" cellpadding="1" cellspacing="0" row_id="1657" txt_name="CITY OF LONDON"><tr><td>513125N 0000547W -<br/>513118N 0000439W -<br/>513043N 0000418W -<br/>513016N 0000433W -<br/>513037N 0000704W -<br/>513108N 0000653W -<br/>513125N 0000547W <br/>Upper limit: 1400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;<br/>any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;<br/>any helicopter flying on Helicopter Route H4;<br/>any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.<br/><br/>See also ENR 1.1, paragraph 4.1.6.<br/><br/>SI 2092/2004.<br/><br/>Contact: www.nats.co.uk/nsf</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.096525,51.5237138889,426.72 -0.1147444444,51.5188833333,426.72 -0.1176944444,51.5102972222,426.72 -0.0757138889,51.5044888889,426.72 -0.0716472222,51.5120666667,426.72 -0.0775861111,51.5216055556,426.72 -0.096525,51.5237138889,426.72 + + + + + + EGR159 ISLE OF DOGS + <table border="1" cellpadding="1" cellspacing="0" row_id="1658" txt_name="ISLE OF DOGS"><tr><td>513035N 0000025W -<br/>512954N 0000033W -<br/>512938N 0000022W thence clockwise by the arc of a circle radius 0.3 NM centred on 512931N 0000049W to<br/>512921N 0000113W -<br/>513000N 0000154W thence clockwise by the arc of a circle radius 0.55 NM centred on 513018N 0000110W to -<br/>513035N 0000025W <br/>Upper limit: 1400 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;<br/>any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;<br/>any helicopter flying on Helicopter Route H4;<br/>any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit;<br/>any aircraft approaching to, or departing from, London/City Airport.<br/><br/>See also ENR 1.1, paragraph 4.1.6.<br/><br/>SI 2091/2004.<br/><br/>Contact: www.nats.co.uk/nsf</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0068583333,51.5097055556,426.72 -0.0082867913,51.5111814939,426.72 -0.0103077723,51.5123684169,426.72 -0.0126486151,51.5132988323,426.72 -0.0152268831,51.5139399674,426.72 -0.0179517632,51.514269238,426.72 -0.020727269,51.514275045,426.72 -0.0234556276,51.5139571838,426.72 -0.0260407298,51.5133268516,426.72 -0.0283915214,51.5124062522,426.72 -0.030425215,51.5112278124,426.72 -0.0320702078,51.5098330386,426.72 -0.0332686036,51.5082710525,426.72 -0.0339782479,51.5065968595,426.72 -0.0341742076,51.5048694103,426.72 -0.0338496416,51.5031495242,426.72 -0.033016033,51.5014977474,426.72 -0.0317027778,51.4999722222,426.72 -0.0202666667,51.4891111111,426.72 -0.0187899397,51.4881604117,426.72 -0.0170196811,51.4874451822,426.72 -0.0150110296,51.4870446916,426.72 -0.0129044713,51.4869869497,426.72 -0.0108473335,51.4872759947,426.72 -0.0089834902,51.4878916114,426.72 -0.0074433086,51.4887907435,426.72 -0.0063345359,51.4899105027,426.72 -0.005734762,51.4911725642,426.72 -0.005685986,51.4924886427,426.72 -0.0061916667,51.4937666667,426.72 -0.0092722222,51.4984027778,426.72 -0.0068583333,51.5097055556,426.72 + + + + + + EGR217 SIZEWELL + <table border="1" cellpadding="1" cellspacing="0" row_id="1080" txt_name="SIZEWELL"><tr><td>A circle, 2 NM radius, centred at 521250N 0013707E <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sizewell, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.6186111111,52.2471767692,609.6 1.6130349418,52.2470002081,609.6 1.6075180128,52.2464724007,609.6 1.602118931,52.2455989541,609.6 1.596895043,52.2443891468,609.6 1.5919018227,52.2428558299,609.6 1.5871922788,52.241015289,609.6 1.5828163894,52.2388870708,609.6 1.5788205702,52.2364937743,609.6 1.5752471812,52.2338608093,609.6 1.5721340772,52.2310161253,609.6 1.5695142078,52.2279899142,609.6 1.5674152705,52.2248142877,609.6 1.5658594196,52.2215229365,609.6 1.5648630359,52.2181507711,609.6 1.5644365577,52.2147335516,609.6 1.5645843754,52.2113075073,609.6 1.5653047901,52.2079089532,609.6 1.5665900379,52.2045739043,609.6 1.5684263769,52.201337695,609.6 1.5707942383,52.198234605,609.6 1.5736684378,52.1952974968,609.6 1.5770184465,52.192557469,609.6 1.5808087168,52.190043528,609.6 1.5849990611,52.1877822821,609.6 1.5895450777,52.1857976613,609.6 1.5943986212,52.184110665,609.6 1.5995083107,52.1827391416,609.6 1.6048200718,52.1816975999,609.6 1.6102777059,52.1809970574,609.6 1.6158234815,52.1806449239,609.6 1.6213987407,52.1806449239,609.6 1.6269445163,52.1809970574,609.6 1.6324021504,52.1816975999,609.6 1.6377139115,52.1827391416,609.6 1.642823601,52.184110665,609.6 1.6476771445,52.1857976613,609.6 1.6522231611,52.1877822821,609.6 1.6564135054,52.190043528,609.6 1.6602037757,52.192557469,609.6 1.6635537844,52.1952974968,609.6 1.6664279839,52.198234605,609.6 1.6687958453,52.201337695,609.6 1.6706321843,52.2045739043,609.6 1.6719174321,52.2079089532,609.6 1.6726378469,52.2113075073,609.6 1.6727856645,52.2147335516,609.6 1.6723591863,52.2181507711,609.6 1.6713628027,52.2215229365,609.6 1.6698069517,52.2248142877,609.6 1.6677080144,52.2279899142,609.6 1.6650881451,52.2310161253,609.6 1.661975041,52.2338608093,609.6 1.658401652,52.2364937743,609.6 1.6544058329,52.2388870708,609.6 1.6500299435,52.241015289,609.6 1.6453203995,52.2428558299,609.6 1.6403271792,52.2443891468,609.6 1.6351032913,52.2455989541,609.6 1.6297042095,52.2464724007,609.6 1.6241872805,52.2470002081,609.6 1.6186111111,52.2471767692,609.6 + + + + + + EGR219 SANDRINGHAM HOUSE + <table border="1" cellpadding="1" cellspacing="0" row_id="1155" txt_name="SANDRINGHAM HOUSE"><tr><td>524819N 0003104E thence clockwise by the arc of a circle radius 1.5 NM centred on 524948N 0003049E to<br/>525117N 0003033E -<br/>525132N 0003424E thence anti-clockwise by the arc of a circle radius 1.5 NM centred on 525003N 0003447E to<br/>524834N 0003510E -<br/>524819N 0003104E <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of National Police Air Service;<br/>any aircraft flying in the service of the Helicopter Emergency Medical Service;<br/>any aircraft flying in the service of the Maritime and Coastguard Agency;<br/>any aircraft flying in the service of The King's Helicopter Flight;<br/>any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;<br/>any aircraft landing in the grounds of Sandringham House at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended landing.<br/><br/>SI 1734/2015.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5177777778,52.8052777778,609.6 0.5861111111,52.8094444444,609.6 0.5813312013,52.8091625577,609.6 0.5765296282,52.8092184194,609.6 0.5717711605,52.8096115099,609.6 0.5671200484,52.8103365217,609.6 0.5626390999,52.8113836653,609.6 0.5583888366,52.8127388006,609.6 0.5544266794,52.8143836274,609.6 0.5508061755,52.8162959307,609.6 0.5475762763,52.8184498803,609.6 0.5447806761,52.8208163777,609.6 0.5424572208,52.8233634481,609.6 0.5406373936,52.8260566712,609.6 0.5393458868,52.8288596452,609.6 0.5386002629,52.8317344777,609.6 0.5384107123,52.8346422975,609.6 0.5387799094,52.8375437796,609.6 0.5397029712,52.8403996768,609.6 0.5411675166,52.8431713511,609.6 0.5431538286,52.8458212968,609.6 0.5456351161,52.8483136486,609.6 0.5485778725,52.8506146684,609.6 0.5519423253,52.8526932029,609.6 0.5556829735,52.8545211069,609.6 0.559749202,52.8560736255,609.6 0.5640859678,52.8573297311,609.6 0.5686345472,52.8582724089,609.6 0.5733333333,52.8588888889,609.6 0.5091666667,52.8547222222,609.6 0.5044716918,52.8542266656,609.6 0.4998968511,52.8534221775,609.6 0.4955069903,52.8523021167,609.6 0.4913613019,52.8508815899,609.6 0.4875156698,52.8491797549,609.6 0.4840219144,52.8472195607,609.6 0.4809270925,52.8450274369,609.6 0.4782728636,52.8426329362,609.6 0.4760949294,52.8400683345,609.6 0.4744225554,52.8373681946,609.6 0.4732781803,52.8345688996,609.6 0.4726771184,52.8317081614,609.6 0.4726273583,52.8288245125,609.6 0.4731294608,52.825956786,609.6 0.4741765578,52.8231435933,609.6 0.4757544502,52.8204228042,609.6 0.4778418043,52.8178310377,609.6 0.4804104435,52.81540317,609.6 0.483425732,52.8131718661,609.6 0.4868470429,52.8111671417,609.6 0.4906283068,52.8094159609,609.6 0.4947186319,52.8079418741,609.6 0.4990629881,52.8067647034,609.6 0.5036029447,52.8059002767,609.6 0.5082774536,52.8053602162,609.6 0.513023667,52.8051517825,609.6 0.5177777778,52.8052777778,609.6 + + + + + + EGR220 ANMER HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="1135" txt_name="ANMER HALL"><tr><td>A circle, 1.5 NM radius, centred at 525003N 0003447E <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>any aircraft in the service of National Police Air Service;<br/>any aircraft flying in the service of the Helicopter Emergency Medical Service;<br/>any aircraft flying in the service of the Maritime and Coastguard Agency;<br/>any aircraft flying in the service of The King's Helicopter Flight;<br/>any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;<br/>any aircraft either operated by a member of the Royal Family, or landing in the grounds of Anmer Hall at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended flight or landing.<br/><br/>SI 1735/2015.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5797222222,52.859129963,609.6 0.5748442042,52.8589546483,609.6 0.5700347793,52.8584311691,609.6 0.5653615715,52.8575668864,609.6 0.5608902795,52.8563739525,609.6 0.5566837497,52.8548691396,609.6 0.5528010891,52.8530736028,609.6 0.5492968325,52.8510125816,609.6 0.5462201754,52.8487150433,609.6 0.5436142829,52.846213275,609.6 0.5415156856,52.8435424277,609.6 0.539953769,52.8407400216,609.6 0.5389503657,52.8378454177,609.6 0.5385194541,52.8348992641,609.6 0.5386669678,52.8319429244,609.6 0.5393907192,52.829017897,609.6 0.5406804363,52.8261652326,609.6 0.5425179136,52.8234249585,609.6 0.5448772732,52.8208355175,609.6 0.5477253323,52.8184332298,609.6 0.5510220733,52.8162517851,609.6 0.5547212068,52.814321771,609.6 0.5587708226,52.8126702457,609.6 0.5631141169,52.8113203607,609.6 0.5676901877,52.8102910367,609.6 0.5724348857,52.8095967002,609.6 0.5772817097,52.8092470821,609.6 0.5821627347,52.8092470821,609.6 0.5870095588,52.8095967002,609.6 0.5917542567,52.8102910367,609.6 0.5963303275,52.8113203607,609.6 0.6006736219,52.8126702457,609.6 0.6047232376,52.814321771,609.6 0.6084223711,52.8162517851,609.6 0.6117191121,52.8184332298,609.6 0.6145671713,52.8208355175,609.6 0.6169265308,52.8234249585,609.6 0.6187640082,52.8261652326,609.6 0.6200537253,52.829017897,609.6 0.6207774766,52.8319429244,609.6 0.6209249903,52.8348992641,609.6 0.6204940787,52.8378454177,609.6 0.6194906755,52.8407400216,609.6 0.6179287589,52.8435424277,609.6 0.6158301615,52.846213275,609.6 0.613224269,52.8487150433,609.6 0.6101476119,52.8510125816,609.6 0.6066433553,52.8530736028,609.6 0.6027606947,52.8548691396,609.6 0.5985541649,52.8563739525,609.6 0.594082873,52.8575668864,609.6 0.5894096651,52.8584311691,609.6 0.5846002403,52.8589546483,609.6 0.5797222222,52.859129963,609.6 + + + + + + EGR311 CAPENHURST + <table border="1" cellpadding="1" cellspacing="0" row_id="1081" txt_name="CAPENHURST"><tr><td>A circle, 2 NM radius, centred at 531550N 0025708W <br/>Upper limit: 2200 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9522222222,53.2971708423,670.5600000000001 -2.9579341894,53.2969943076,670.5600000000001 -2.9635854683,53.2964665791,670.5600000000001 -2.9691160199,53.2955932635,670.5600000000001 -2.9744670965,53.2943836389,670.5600000000001 -2.9795818698,53.2928505553,670.5600000000001 -2.9844060374,53.2910102972,670.5600000000001 -2.9888884027,53.2888824097,670.5600000000001 -2.9929814192,53.2864894898,670.5600000000001 -2.9966416966,53.2838569448,670.5600000000001 -2.9998304605,53.2810127215,670.5600000000001 -3.0025139625,53.2779870081,670.5600000000001 -3.0046638354,53.2748119126,670.5600000000001 -3.0062573909,53.2715211209,670.5600000000001 -3.0072778557,53.2681495386,670.5600000000001 -3.0077145442,53.26473292,670.5600000000001 -3.0075629662,53.2613074885,670.5600000000001 -3.0068248687,53.2579095522,670.5600000000001 -3.0055082113,53.2545751195,670.5600000000001 -3.0036270764,53.2513395174,670.5600000000001 -3.0012015142,53.248237018,670.5600000000001 -2.9982573261,53.2453004767,670.5600000000001 -2.9948257867,53.2425609844,670.5600000000001 -2.9909433102,53.2400475405,670.5600000000001 -2.9866510624,53.2377867465,670.5600000000001 -2.981994524,53.2358025259,670.5600000000001 -2.9770230091,53.2341158725,670.5600000000001 -2.9717891449,53.2327446297,670.5600000000001 -2.9663483163,53.2317033022,670.5600000000001 -2.9607580832,53.2310029042,670.5600000000001 -2.955077575,53.2306508436,670.5600000000001 -2.9493668694,53.2306508436,670.5600000000001 -2.9436863612,53.2310029042,670.5600000000001 -2.9380961281,53.2317033022,670.5600000000001 -2.9326552995,53.2327446297,670.5600000000001 -2.9274214353,53.2341158725,670.5600000000001 -2.9224499205,53.2358025259,670.5600000000001 -2.917793382,53.2377867465,670.5600000000001 -2.9135011342,53.2400475405,670.5600000000001 -2.9096186577,53.2425609844,670.5600000000001 -2.9061871184,53.2453004767,670.5600000000001 -2.9032429302,53.248237018,670.5600000000001 -2.9008173681,53.2513395174,670.5600000000001 -2.8989362332,53.2545751195,670.5600000000001 -2.8976195758,53.2579095522,670.5600000000001 -2.8968814782,53.2613074885,670.5600000000001 -2.8967299002,53.26473292,670.5600000000001 -2.8971665887,53.2681495386,670.5600000000001 -2.8981870536,53.2715211209,670.5600000000001 -2.8997806091,53.2748119126,670.5600000000001 -2.901930482,53.2779870081,670.5600000000001 -2.9046139839,53.2810127215,670.5600000000001 -2.9078027478,53.2838569448,670.5600000000001 -2.9114630252,53.2864894898,670.5600000000001 -2.9155560417,53.2888824097,670.5600000000001 -2.920038407,53.2910102972,670.5600000000001 -2.9248625747,53.2928505553,670.5600000000001 -2.9299773479,53.2943836389,670.5600000000001 -2.9353284246,53.2955932635,670.5600000000001 -2.9408589761,53.2964665791,670.5600000000001 -2.946510255,53.2969943076,670.5600000000001 -2.9522222222,53.2971708423,670.5600000000001 + + + + + + EGR312 SPRINGFIELDS + <table border="1" cellpadding="1" cellspacing="0" row_id="1082" txt_name="SPRINGFIELDS"><tr><td>A circle, 2 NM radius, centred at 534634N 0024815W <br/>Upper limit: 2100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted at not less than 1670 FT above mean sea level for the purpose of landing at Blackpool Airport.<br/><br/>Flight permitted in airspace lying south of a straight line drawn from 534644N 0024454W to 534513N 0025044W for the purpose of landing at or taking off from Warton Aerodrome.<br/><br/>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Springfields, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8041666667,53.8093901962,640.08 -2.8099480329,53.8092136741,640.08 -2.8156679709,53.8086859834,640.08 -2.8212657095,53.8078127308,640.08 -2.8266817852,53.8066031939,640.08 -2.8318586771,53.8050702223,640.08 -2.836741422,53.8032301001,640.08 -2.8412782002,53.8011023716,640.08 -2.8454208877,53.7987096328,640.08 -2.8491255674,53.7960772901,640.08 -2.852352995,53.7932332887,640.08 -2.855069014,53.7902078153,640.08 -2.857244915,53.787032976,640.08 -2.8588577369,53.7837424545,640.08 -2.859890506,53.780371154,640.08 -2.8603324101,53.7769548261,640.08 -2.8601789083,53.7735296912,640.08 -2.8594317722,53.7701320543,640.08 -2.8580990616,53.7667979202,640.08 -2.8561950329,53.7635626126,640.08 -2.8537399825,53.7604604,640.08 -2.850760027,53.7575241339,640.08 -2.8472868223,53.7547849019,640.08 -2.8433572254,53.7522716996,640.08 -2.839012902,53.7500111253,640.08 -2.8342998842,53.7480270994,640.08 -2.8292680834,53.7463406129,640.08 -2.8239707635,53.7449695067,640.08 -2.8184639791,53.7439282835,640.08 -2.8128059857,53.7432279559,640.08 -2.807056627,53.7428759307,640.08 -2.8012767063,53.7428759307,640.08 -2.7955273476,53.7432279559,640.08 -2.7898693542,53.7439282835,640.08 -2.7843625699,53.7449695067,640.08 -2.7790652499,53.7463406129,640.08 -2.7740334492,53.7480270994,640.08 -2.7693204313,53.7500111253,640.08 -2.7649761079,53.7522716996,640.08 -2.7610465111,53.7547849019,640.08 -2.7575733064,53.7575241339,640.08 -2.7545933508,53.7604604,640.08 -2.7521383004,53.7635626126,640.08 -2.7502342717,53.7667979202,640.08 -2.7489015611,53.7701320543,640.08 -2.748154425,53.7735296912,640.08 -2.7480009232,53.7769548261,640.08 -2.7484428274,53.780371154,640.08 -2.7494755964,53.7837424545,640.08 -2.7510884183,53.787032976,640.08 -2.7532643193,53.7902078153,640.08 -2.7559803383,53.7932332887,640.08 -2.759207766,53.7960772901,640.08 -2.7629124456,53.7987096328,640.08 -2.7670551331,53.8011023716,640.08 -2.7715919114,53.8032301001,640.08 -2.7764746563,53.8050702223,640.08 -2.7816515482,53.8066031939,640.08 -2.7870676238,53.8078127308,640.08 -2.7926653624,53.8086859834,640.08 -2.7983853004,53.8092136741,640.08 -2.8041666667,53.8093901962,640.08 + + + + + + EGR313 SCAMPTON + <table border="1" cellpadding="1" cellspacing="0" row_id="1728" txt_name="SCAMPTON"><tr><td>A circle, 5 NM radius, centred at 531828N 0003303W <br/>Upper limit: 9500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Contact: Information on activation status may be obtained from Waddington ATC, Tel: 01522-727451/727452, or by radio to Waddington Zone on 119.500 MHz/232.700 MHz.<br/><br/>Non-radio aircraft may be able to obtain a pre-flight clearance by telephone. Radio equipped aircraft may request an in-flight clearance to enter EGR313 from Waddington Zone on 119.500/232.700 MHz.<br/><br/>SI 2023/879.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5508333333,53.3909816953,2895.6000000000004 -0.559936563,53.3908032038,2895.6000000000004 -0.5690005838,53.3902684981,2895.6000000000004 -0.5779863586,53.389379881,2895.6000000000004 -0.5868551933,53.3881411797,2895.6000000000004 -0.595568906,53.3865577284,2895.6000000000004 -0.6040899938,53.3846363454,2895.6000000000004 -0.6123817972,53.382385303,2895.6000000000004 -0.6204086597,53.3798142914,2895.6000000000004 -0.6281360829,53.3769343765,2895.6000000000004 -0.6355308768,53.3737579512,2895.6000000000004 -0.6425613032,53.3702986815,2895.6000000000004 -0.6491972133,53.366571447,2895.6000000000004 -0.6554101771,53.3625922757,2895.6000000000004 -0.6611736056,53.3583782744,2895.6000000000004 -0.6664628642,53.3539475544,2895.6000000000004 -0.6712553778,53.3493191525,2895.6000000000004 -0.6755307254,53.3445129487,2895.6000000000004 -0.6792707268,53.33954958,2895.6000000000004 -0.6824595172,53.3344503507,2895.6000000000004 -0.6850836134,53.3292371409,2895.6000000000004 -0.687131968,53.3239323115,2895.6000000000004 -0.6885960136,53.3185586082,2895.6000000000004 -0.6894696963,53.3131390634,2895.6000000000004 -0.6897494974,53.3076968973,2895.6000000000004 -0.6894344449,53.3022554181,2895.6000000000004 -0.688526114,53.2968379224,2895.6000000000004 -0.687028616,53.2914675952,2895.6000000000004 -0.6849485775,53.2861674113,2895.6000000000004 -0.6822951079,53.2809600368,2895.6000000000004 -0.6790797571,53.2758677328,2895.6000000000004 -0.6753164628,53.2709122608,2895.6000000000004 -0.6710214883,53.2661147902,2895.6000000000004 -0.6662133499,53.2614958084,2895.6000000000004 -0.6609127355,53.2570750343,2895.6000000000004 -0.6551424149,53.2528713345,2895.6000000000004 -0.6489271405,53.2489026439,2895.6000000000004 -0.6422935407,53.2451858903,2895.6000000000004 -0.6352700061,53.2417369221,2895.6000000000004 -0.6278865676,53.2385704427,2895.6000000000004 -0.6201747691,53.235699948,2895.6000000000004 -0.6121675334,53.2331376696,2895.6000000000004 -0.6038990228,53.230894524,2895.6000000000004 -0.5954044954,53.2289800663,2895.6000000000004 -0.5867201563,53.2274024504,2895.6000000000004 -0.5778830057,53.2261683946,2895.6000000000004 -0.5689306834,53.2252831538,2895.6000000000004 -0.5599013112,53.2247504972,2895.6000000000004 -0.5508333333,53.2245726926,2895.6000000000004 -0.5417653554,53.2247504972,2895.6000000000004 -0.5327359832,53.2252831538,2895.6000000000004 -0.5237836609,53.2261683946,2895.6000000000004 -0.5149465103,53.2274024504,2895.6000000000004 -0.5062621713,53.2289800663,2895.6000000000004 -0.4977676439,53.230894524,2895.6000000000004 -0.4894991333,53.2331376696,2895.6000000000004 -0.4814918975,53.235699948,2895.6000000000004 -0.473780099,53.2385704427,2895.6000000000004 -0.4663966606,53.2417369221,2895.6000000000004 -0.459373126,53.2451858903,2895.6000000000004 -0.4527395262,53.2489026439,2895.6000000000004 -0.4465242517,53.2528713345,2895.6000000000004 -0.4407539311,53.2570750343,2895.6000000000004 -0.4354533168,53.2614958084,2895.6000000000004 -0.4306451783,53.2661147902,2895.6000000000004 -0.4263502038,53.2709122608,2895.6000000000004 -0.4225869096,53.2758677328,2895.6000000000004 -0.4193715588,53.2809600368,2895.6000000000004 -0.4167180891,53.2861674113,2895.6000000000004 -0.4146380506,53.2914675952,2895.6000000000004 -0.4131405527,53.2968379224,2895.6000000000004 -0.4122322218,53.3022554181,2895.6000000000004 -0.4119171693,53.3076968973,2895.6000000000004 -0.4121969703,53.3131390634,2895.6000000000004 -0.413070653,53.3185586082,2895.6000000000004 -0.4145346987,53.3239323115,2895.6000000000004 -0.4165830533,53.3292371409,2895.6000000000004 -0.4192071494,53.3344503507,2895.6000000000004 -0.4223959399,53.33954958,2895.6000000000004 -0.4261359412,53.3445129487,2895.6000000000004 -0.4304112889,53.3493191525,2895.6000000000004 -0.4352038024,53.3539475544,2895.6000000000004 -0.4404930611,53.3583782744,2895.6000000000004 -0.4462564895,53.3625922757,2895.6000000000004 -0.4524694533,53.366571447,2895.6000000000004 -0.4591053634,53.3702986815,2895.6000000000004 -0.4661357899,53.3737579512,2895.6000000000004 -0.4735305838,53.3769343765,2895.6000000000004 -0.481258007,53.3798142914,2895.6000000000004 -0.4892848694,53.382385303,2895.6000000000004 -0.4975766729,53.3846363454,2895.6000000000004 -0.5060977607,53.3865577284,2895.6000000000004 -0.5148114733,53.3881411797,2895.6000000000004 -0.5236803081,53.389379881,2895.6000000000004 -0.5326660829,53.3902684981,2895.6000000000004 -0.5417301037,53.3908032038,2895.6000000000004 -0.5508333333,53.3909816953,2895.6000000000004 + + + + + + EGR322 WYLFA + <table border="1" cellpadding="1" cellspacing="0" row_id="1086" txt_name="WYLFA"><tr><td>A circle, 2 NM radius, centred at 532458N 0042852W <br/>Upper limit: 2100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted at a height of not less than 2000 FT above ground level whilst operating under and in accordance with a clearance from the air traffic control unit at RAF Valley.<br/><br/>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Wylfa, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4812194444,53.4493672106,640.08 -4.4869518094,53.4491906797,640.08 -4.4926232685,53.4486629624,640.08 -4.4981735678,53.4477896656,640.08 -4.5035437489,53.4465800672,640.08 -4.5086767801,53.445047017,640.08 -4.5135181648,53.4432067994,640.08 -4.5180165232,53.4410789594,640.08 -4.5221241391,53.4386860935,640.08 -4.5257974674,53.4360536087,640.08 -4.5289975955,53.4332094516,640.08 -4.531690655,53.4301838097,640.08 -4.5338481782,53.4270087905,640.08 -4.5354473967,53.4237180793,640.08 -4.5364714781,53.4203465809,640.08 -4.5369096997,53.4169300489,640.08 -4.5367575564,53.4135047057,640.08 -4.5360168024,53.4101068585,640.08 -4.5346954268,53.4067725146,640.08 -4.532807563,53.4035370001,640.08 -4.5303733337,53.4004345861,640.08 -4.5274186328,53.3974981266,640.08 -4.5239748471,53.3947587118,640.08 -4.5200785209,53.3922453397,640.08 -4.5157709669,53.389984611,640.08 -4.5110978279,53.3880004483,640.08 -4.5061085937,53.3863138446,640.08 -4.5008560783,53.3849426423,640.08 -4.4953958637,53.3839013458,640.08 -4.4897857142,53.3832009688,640.08 -4.4840849692,53.3828489187,640.08 -4.4783539196,53.3828489187,640.08 -4.4726531746,53.3832009688,640.08 -4.4670430252,53.3839013458,640.08 -4.4615828106,53.3849426423,640.08 -4.4563302952,53.3863138446,640.08 -4.451341061,53.3880004483,640.08 -4.4466679219,53.389984611,640.08 -4.442360368,53.3922453397,640.08 -4.4384640418,53.3947587118,640.08 -4.4350202561,53.3974981266,640.08 -4.4320655552,53.4004345861,640.08 -4.4296313259,53.4035370001,640.08 -4.4277434621,53.4067725146,640.08 -4.4264220865,53.4101068585,640.08 -4.4256813325,53.4135047057,640.08 -4.4255291891,53.4169300489,640.08 -4.4259674108,53.4203465809,640.08 -4.4269914922,53.4237180793,640.08 -4.4285907107,53.4270087905,640.08 -4.4307482339,53.4301838097,640.08 -4.4334412934,53.4332094516,640.08 -4.4366414215,53.4360536087,640.08 -4.4403147498,53.4386860935,640.08 -4.4444223657,53.4410789594,640.08 -4.4489207241,53.4432067994,640.08 -4.4537621088,53.445047017,640.08 -4.45889514,53.4465800672,640.08 -4.4642653211,53.4477896656,640.08 -4.4698156203,53.4486629624,640.08 -4.4754870795,53.4491906797,640.08 -4.4812194444,53.4493672106,640.08 + + + + + + EGR413 SELLAFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="1087" txt_name="SELLAFIELD"><tr><td>A circle, 2 NM radius, centred at 542505N 0032944W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sellafield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4955555556,54.451331069,609.6 -3.5014269937,54.4511545625,609.6 -3.5072360431,54.4506269186,609.6 -3.5129209825,54.4497537438,609.6 -3.5184214188,54.4485443153,609.6 -3.5236789329,54.4470114824,609.6 -3.5286377032,54.4451715284,609.6 -3.5332451019,54.4430439969,609.6 -3.537452255,54.4406514827,609.6 -3.5412145619,54.4380193906,609.6 -3.5444921685,54.4351756646,609.6 -3.5472503885,54.4321504892,609.6 -3.5494600685,54.4289759681,609.6 -3.5510978936,54.4256857826,609.6 -3.5521466295,54.4223148326,609.6 -3.5525953007,54.4188988665,609.6 -3.5524392998,54.415474101,609.6 -3.551680431,54.4120768371,609.6 -3.5503268838,54.4087430754,609.6 -3.5483931406,54.4055081352,609.6 -3.5458998173,54.4024062804,609.6 -3.54287344,54.399470358,609.6 -3.5393461593,54.3967314511,609.6 -3.535355407,54.3942185508,609.6 -3.5309434975,54.3919582512,609.6 -3.5261571785,54.3899744688,609.6 -3.5210471366,54.388288191,609.6 -3.5156674621,54.3869172556,609.6 -3.5100750787,54.3858761629,609.6 -3.5043291446,54.3851759235,609.6 -3.4984904303,54.3848239427,609.6 -3.4926206808,54.3848239427,609.6 -3.4867819665,54.3851759235,609.6 -3.4810360324,54.3858761629,609.6 -3.475443649,54.3869172556,609.6 -3.4700639745,54.388288191,609.6 -3.4649539326,54.3899744688,609.6 -3.4601676136,54.3919582512,609.6 -3.4557557041,54.3942185508,609.6 -3.4517649518,54.3967314511,609.6 -3.4482376711,54.399470358,609.6 -3.4452112938,54.4024062804,609.6 -3.4427179705,54.4055081352,609.6 -3.4407842274,54.4087430754,609.6 -3.4394306801,54.4120768371,609.6 -3.4386718113,54.415474101,609.6 -3.4385158104,54.4188988665,609.6 -3.4389644816,54.4223148326,609.6 -3.4400132175,54.4256857826,609.6 -3.4416510426,54.4289759681,609.6 -3.4438607226,54.4321504892,609.6 -3.4466189426,54.4351756646,609.6 -3.4498965493,54.4380193906,609.6 -3.4536588561,54.4406514827,609.6 -3.4578660092,54.4430439969,609.6 -3.4624734079,54.4451715284,609.6 -3.4674321783,54.4470114824,609.6 -3.4726896923,54.4485443153,609.6 -3.4781901287,54.4497537438,609.6 -3.483875068,54.4506269186,609.6 -3.4896841174,54.4511545625,609.6 -3.4955555556,54.451331069,609.6 + + + + + + EGR444 HEYSHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="1090" txt_name="HEYSHAM"><tr><td>A circle, 2 NM radius, centred at 540147N 0025452W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Heysham, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>Microlight access to Middleton Sands obtained from BMAA head office.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9144222222,54.0630915593,609.6 -2.9202387654,54.0629150434,609.6 -2.9259935051,54.0623873713,609.6 -2.9316252994,54.0615141495,609.6 -2.9370743215,54.0603046557,609.6 -2.9422826999,54.0587717391,609.6 -2.9471951361,54.0569316837,609.6 -2.9517594948,54.0548040333,609.6 -2.955927359,54.0524113837,609.6 -2.9596545448,54.0497791404,609.6 -2.9629015698,54.0469352482,609.6 -2.9656340704,54.0439098929,609.6 -2.9678231638,54.0407351798,609.6 -2.9694457509,54.0374447914,609.6 -2.970484756,54.0340736299,609.6 -2.9709293033,54.0306574453,609.6 -2.9707748258,54.0272324567,609.6 -2.9700231078,54.0238349675,609.6 -2.9686822598,54.0205009808,609.6 -2.9667666265,54.0172658186,609.6 -2.9642966289,54.0141637476,609.6 -2.9612985437,54.0112276176,609.6 -2.9578042199,54.0084885142,609.6 -2.9538507391,54.0059754314,609.6 -2.9494800202,54.0037149657,609.6 -2.9447383748,54.0017310361,609.6 -2.9396760171,54.0000446322,609.6 -2.9343465338,53.9986735935,609.6 -2.9288063188,53.9976324219,609.6 -2.9231139803,53.9969321292,609.6 -2.9173297239,53.9965801216,609.6 -2.9115147206,53.9965801216,609.6 -2.9057304642,53.9969321292,609.6 -2.9000381256,53.9976324219,609.6 -2.8944979107,53.9986735935,609.6 -2.8891684273,54.0000446322,609.6 -2.8841060697,54.0017310361,609.6 -2.8793644243,54.0037149657,609.6 -2.8749937053,54.0059754314,609.6 -2.8710402245,54.0084885142,609.6 -2.8675459008,54.0112276176,609.6 -2.8645478155,54.0141637476,609.6 -2.862077818,54.0172658186,609.6 -2.8601621846,54.0205009808,609.6 -2.8588213367,54.0238349675,609.6 -2.8580696187,54.0272324567,609.6 -2.8579151412,54.0306574453,609.6 -2.8583596884,54.0340736299,609.6 -2.8593986936,54.0374447914,609.6 -2.8610212806,54.0407351798,609.6 -2.8632103741,54.0439098929,609.6 -2.8659428747,54.0469352482,609.6 -2.8691898996,54.0497791404,609.6 -2.8729170854,54.0524113837,609.6 -2.8770849496,54.0548040333,609.6 -2.8816493083,54.0569316837,609.6 -2.8865617445,54.0587717391,609.6 -2.8917701229,54.0603046557,609.6 -2.897219145,54.0615141495,609.6 -2.9028509393,54.0623873713,609.6 -2.908605679,54.0629150434,609.6 -2.9144222222,54.0630915593,609.6 + + + + + + EGR445 BARROW IN FURNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="1092" txt_name="BARROW IN FURNESS"><tr><td>A circle, 0.5 NM radius, centred at 540635N 0031410W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Barrow in Furness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2361111111,54.118041546,609.6 -3.2389617203,54.1178712153,609.6 -3.2416955575,54.1173672007,609.6 -3.2442006422,54.1165501481,609.6 -3.2463743796,54.1154535248,609.6 -3.248127766,54.1141222467,609.6 -3.249389035,54.112610836,609.6 -3.2501065925,54.110981186,609.6 -3.250251122,54.1093000245,609.6 -3.2498167752,54.1076361805,609.6 -3.2488214002,54.1060577659,609.6 -3.2473058003,54.104629388,609.6 -3.2453320547,54.1034095068,609.6 -3.2429809723,54.1024480441,609.6 -3.2403487825,54.1017843434,609.6 -3.2375432,54.1014455622,609.6 -3.2346790222,54.1014455622,609.6 -3.2318734397,54.1017843434,609.6 -3.2292412499,54.1024480441,609.6 -3.2268901675,54.1034095068,609.6 -3.2249164219,54.104629388,609.6 -3.223400822,54.1060577659,609.6 -3.2224054471,54.1076361805,609.6 -3.2219711003,54.1093000245,609.6 -3.2221156297,54.110981186,609.6 -3.2228331872,54.112610836,609.6 -3.2240944562,54.1141222467,609.6 -3.2258478426,54.1154535248,609.6 -3.22802158,54.1165501481,609.6 -3.2305266648,54.1173672007,609.6 -3.2332605019,54.1178712153,609.6 -3.2361111111,54.118041546,609.6 + + + + + + EGR446 HARTLEPOOL + <table border="1" cellpadding="1" cellspacing="0" row_id="1091" txt_name="HARTLEPOOL"><tr><td>A circle, 2 NM radius, centred at 543807N 0011049W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hartlepool, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>Flight at a height of not less than 1800 FT amsl whilst conducting an instrument approach procedure at Teesside International Airport.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1802777778,54.6685520888,609.6 -1.1861805046,54.6683755875,609.6 -1.192020509,54.6678479593,609.6 -1.1977357397,54.6669748105,609.6 -1.2032654807,54.6657654184,609.6 -1.2085510006,54.6642326319,609.6 -1.2135361801,54.6623927343,609.6 -1.2181681102,54.6602652688,609.6 -1.2223976566,54.6578728299,609.6 -1.2261799812,54.655240822,609.6 -1.2294750182,54.6523971884,609.6 -1.2322478972,54.649372113,609.6 -1.2344693105,54.646197699,609.6 -1.2361158203,54.6429076263,609.6 -1.2371701022,54.6395367943,609.6 -1.2376211234,54.63612095,609.6 -1.2374642539,54.6326963088,609.6 -1.2367013088,54.6292991706,609.6 -1.2353405231,54.6259655344,609.6 -1.2333964576,54.622730718,609.6 -1.2308898392,54.6196289839,609.6 -1.2278473362,54.6166931775,609.6 -1.224301271,54.6139543803,609.6 -1.2202892752,54.611441582,609.6 -1.2158538885,54.6091813752,609.6 -1.2110421072,54.607197675,609.6 -1.2059048872,54.6055114677,609.6 -1.2004966058,54.6041405901,609.6 -1.1948744885,54.6030995414,609.6 -1.189098007,54.6023993318,609.6 -1.1832282541,54.602047366,609.6 -1.1773273015,54.602047366,609.6 -1.1714575485,54.6023993318,609.6 -1.1656810671,54.6030995414,609.6 -1.1600589498,54.6041405901,609.6 -1.1546506683,54.6055114677,609.6 -1.1495134483,54.607197675,609.6 -1.144701667,54.6091813752,609.6 -1.1402662803,54.611441582,609.6 -1.1362542845,54.6139543803,609.6 -1.1327082194,54.6166931775,609.6 -1.1296657163,54.6196289839,609.6 -1.127159098,54.622730718,609.6 -1.1252150324,54.6259655344,609.6 -1.1238542467,54.6292991706,609.6 -1.1230913017,54.6326963088,609.6 -1.1229344322,54.63612095,609.6 -1.1233854534,54.6395367943,609.6 -1.1244397352,54.6429076263,609.6 -1.126086245,54.646197699,609.6 -1.1283076584,54.649372113,609.6 -1.1310805374,54.6523971884,609.6 -1.1343755744,54.655240822,609.6 -1.138157899,54.6578728299,609.6 -1.1423874453,54.6602652688,609.6 -1.1470193755,54.6623927343,609.6 -1.1520045549,54.6642326319,609.6 -1.1572900749,54.6657654184,609.6 -1.1628198159,54.6669748105,609.6 -1.1685350466,54.6678479593,609.6 -1.1743750509,54.6683755875,609.6 -1.1802777778,54.6685520888,609.6 + + + + + + EGR515 HUNTERSTON + <table border="1" cellpadding="1" cellspacing="0" row_id="1103" txt_name="HUNTERSTON"><tr><td>A circle, 2 NM radius, centred at 554317N 0045338W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hunterston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.8938888889,55.7546572369,609.6 -4.8999545473,55.7544807614,609.6 -4.9059557454,55.7539532102,609.6 -4.9118287131,55.7530801894,609.6 -4.9175110532,55.751870976,609.6 -4.9229424086,55.7503384181,609.6 -4.9280651075,55.748498798,609.6 -4.9328247789,55.7463716576,609.6 -4.9371709319,55.7439795898,609.6 -4.941057492,55.7413479969,609.6 -4.9444432906,55.7385048196,609.6 -4.9472924991,55.7354802387,609.6 -4.9495750068,55.7323063534,609.6 -4.9512667358,55.7290168396,609.6 -4.9523498915,55.7256465915,609.6 -4.9528131451,55.7222313507,609.6 -4.9526517473,55.7188073265,609.6 -4.9518675721,55.7154108119,609.6 -4.9504690896,55.7120777991,609.6 -4.9484712699,55.7088435984,609.6 -4.9458954179,55.7057424646,609.6 -4.9427689426,55.7028072354,609.6 -4.9391250617,55.7000689844,609.6 -4.9350024464,55.697556694,609.6 -4.9304448098,55.6952969494,609.6 -4.9255004428,55.6933136592,609.6 -4.9202217032,55.6916278036,609.6 -4.9146644628,55.6902572139,609.6 -4.908887519,55.6892163852,609.6 -4.9029519762,55.6885163242,609.6 -4.8969206031,55.6881644332,609.6 -4.8908571746,55.6881644332,609.6 -4.8848258016,55.6885163242,609.6 -4.8788902587,55.6892163852,609.6 -4.873113315,55.6902572139,609.6 -4.8675560746,55.6916278036,609.6 -4.862277335,55.6933136592,609.6 -4.8573329679,55.6952969494,609.6 -4.8527753314,55.697556694,609.6 -4.8486527161,55.7000689844,609.6 -4.8450088351,55.7028072354,609.6 -4.8418823598,55.7057424646,609.6 -4.8393065079,55.7088435984,609.6 -4.8373086881,55.7120777991,609.6 -4.8359102057,55.7154108119,609.6 -4.8351260305,55.7188073265,609.6 -4.8349646327,55.7222313507,609.6 -4.8354278863,55.7256465915,609.6 -4.836511042,55.7290168396,609.6 -4.838202771,55.7323063534,609.6 -4.8404852787,55.7354802387,609.6 -4.8433344872,55.7385048196,609.6 -4.8467202857,55.7413479969,609.6 -4.8506068459,55.7439795898,609.6 -4.8549529988,55.7463716576,609.6 -4.8597126703,55.748498798,609.6 -4.8648353692,55.7503384181,609.6 -4.8702667246,55.751870976,609.6 -4.8759490647,55.7530801894,609.6 -4.8818220324,55.7539532102,609.6 -4.8878232305,55.7544807614,609.6 -4.8938888889,55.7546572369,609.6 + + + + + + EGR516 TORNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="1104" txt_name="TORNESS"><tr><td>A circle, 2 NM radius, centred at 555806N 0022431W <br/>Upper limit: 2100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Torness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4084777778,56.0015392269,640.08 -2.4145820483,56.0013627571,640.08 -2.4206214466,56.0008352231,640.08 -2.4265317954,55.9999622309,640.08 -2.4322502988,55.9987530573,640.08 -2.4377162144,55.9972205504,640.08 -2.4428715028,55.9953809923,640.08 -2.4476614461,55.9932539246,640.08 -2.4520352321,55.9908619399,640.08 -2.4559464934,55.98823044,640.08 -2.4593537998,55.985387365,640.08 -2.4622210959,55.982362895,640.08 -2.4645180807,55.9791891284,640.08 -2.4662205246,55.9758997402,640.08 -2.4673105215,55.9725296235,640.08 -2.4677766727,55.9691145185,640.08 -2.4676142006,55.9656906333,640.08 -2.4668249932,55.9622942594,640.08 -2.4654175764,55.9589613873,640.08 -2.4634070172,55.9557273257,640.08 -2.4608147578,55.9526263276,640.08 -2.4576683825,55.9496912288,640.08 -2.4540013212,55.9469531015,640.08 -2.4498524916,55.9444409261,640.08 -2.4452658848,55.9421812862,640.08 -2.4402900985,55.9401980889,640.08 -2.4349778227,55.938512313,640.08 -2.4293852834,55.9371417886,640.08 -2.4235716504,55.9361010098,640.08 -2.4175984149,55.9354009824,640.08 -2.4115287429,55.9350491084,640.08 -2.4054268127,55.9350491084,640.08 -2.3993571407,55.9354009824,640.08 -2.3933839051,55.9361010098,640.08 -2.3875702722,55.9371417886,640.08 -2.3819777329,55.938512313,640.08 -2.376665457,55.9401980889,640.08 -2.3716896707,55.9421812862,640.08 -2.367103064,55.9444409261,640.08 -2.3629542344,55.9469531015,640.08 -2.3592871731,55.9496912288,640.08 -2.3561407978,55.9526263276,640.08 -2.3535485383,55.9557273257,640.08 -2.3515379792,55.9589613873,640.08 -2.3501305624,55.9622942594,640.08 -2.3493413549,55.9656906333,640.08 -2.3491788829,55.9691145185,640.08 -2.3496450341,55.9725296235,640.08 -2.350735031,55.9758997402,640.08 -2.3524374749,55.9791891284,640.08 -2.3547344596,55.982362895,640.08 -2.3576017558,55.985387365,640.08 -2.3610090622,55.98823044,640.08 -2.3649203235,55.9908619399,640.08 -2.3692941094,55.9932539246,640.08 -2.3740840528,55.9953809923,640.08 -2.3792393411,55.9972205504,640.08 -2.3847052568,55.9987530573,640.08 -2.3904237602,55.9999622309,640.08 -2.3963341089,56.0008352231,640.08 -2.4023735073,56.0013627571,640.08 -2.4084777778,56.0015392269,640.08 + + + + + + EGR603 ROSYTH + <table border="1" cellpadding="1" cellspacing="0" row_id="1105" txt_name="ROSYTH"><tr><td>A circle, 0.5 NM radius, centred at 560147N 0032703W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted within the route notified as the Kelty Lane for the purpose of making an approach to land at, or a departure from, Edinburgh Airport.<br/><br/>SI 1003/2016.<br/><br/>Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4508333333,56.0380389069,609.6 -3.4538238226,56.0378686278,609.6 -3.4566918046,56.0373647659,609.6 -3.4593197998,56.036547962,609.6 -3.4616001767,56.0354516743,609.6 -3.4634395644,56.0341208066,609.6 -3.464762678,56.0326098656,609.6 -3.4655153966,56.0309807265,609.6 -3.4656669719,56.0293000971,609.6 -3.465211276,56.0276367846,609.6 -3.4641670394,56.0260588788,609.6 -3.4625770722,56.0246309652,609.6 -3.4605065022,56.0234114834,609.6 -3.4580401027,56.0224503374,609.6 -3.4552788212,56.0217868563,609.6 -3.4523356513,56.0214481874,609.6 -3.4493310153,56.0214481874,609.6 -3.4463878455,56.0217868563,609.6 -3.443626564,56.0224503374,609.6 -3.4411601645,56.0234114834,609.6 -3.4390895945,56.0246309652,609.6 -3.4374996273,56.0260588788,609.6 -3.4364553907,56.0276367846,609.6 -3.4359996948,56.0293000971,609.6 -3.4361512701,56.0309807265,609.6 -3.4369039887,56.0326098656,609.6 -3.4382271022,56.0341208066,609.6 -3.44006649,56.0354516743,609.6 -3.4423468668,56.036547962,609.6 -3.4449748621,56.0373647659,609.6 -3.447842844,56.0378686278,609.6 -3.4508333333,56.0380389069,609.6 + + + + + + EGR610A THE HIGHLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="1660" txt_name="THE HIGHLANDS"><tr><td>583000N 0033902W -<br/>582828N 0033815W -<br/>582356N 0032847W -<br/>580345N 0041248W -<br/>580300N 0043000W -<br/>580000N 0043700W -<br/>574700N 0042500W -<br/>573900N 0043000W -<br/>573800N 0044500W -<br/>573000N 0043800W -<br/>571800N 0045200W -<br/>571100N 0045300W -<br/>570900N 0050000W -<br/>570000N 0050200W -<br/>565400N 0050500W -<br/>565600N 0054700W -<br/>571300N 0053500W -<br/>575000N 0054300W -<br/>580000N 0051500W -<br/>583000N 0044900W -<br/>583000N 0043000W -<br/>582500N 0043000W -<br/>583000N 0042000W -<br/>583000N 0033902W <br/>Upper limit: 5000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Military Airspace Management Cell - Low Flying (MAMC LF) at RAF (U) Swanwick, Tel: 01489-443100.<br/><br/>In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.<br/><br/>Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.<br/><br/>New SI issued on activation.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.6505555556,58.5,1524.0 -4.3333333333,58.5,1524.0 -4.5,58.4166666667,1524.0 -4.5,58.5,1524.0 -4.8166666667,58.5,1524.0 -5.25,58.0,1524.0 -5.7166666667,57.8333333333,1524.0 -5.5833333333,57.2166666667,1524.0 -5.7833333333,56.9333333333,1524.0 -5.0833333333,56.9,1524.0 -5.0333333333,57.0,1524.0 -5.0,57.15,1524.0 -4.8833333333,57.1833333333,1524.0 -4.8666666667,57.3,1524.0 -4.6333333333,57.5,1524.0 -4.75,57.6333333333,1524.0 -4.5,57.65,1524.0 -4.4166666667,57.7833333333,1524.0 -4.6166666667,58.0,1524.0 -4.5,58.05,1524.0 -4.2133333333,58.0625,1524.0 -3.4798583333,58.39885,1524.0 -3.6375,58.4744444444,1524.0 -3.6505555556,58.5,1524.0 + + + + + + EGR610B THE HIGHLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="1670" txt_name="THE HIGHLANDS"><tr><td>575000N 0054300W -<br/>574004N 0054050W -<br/>573840N 0055739W -<br/>570000N 0055644W -<br/>570000N 0061504W -<br/>574715N 0061637W -<br/>575000N 0054300W <br/>Upper limit: 5000 FT MSL<br/>Lower limit: 750 FT MSL<br/>Class: </td><td>When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100.<br/><br/>In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.<br/><br/>Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.<br/><br/>New SI issued on activation.</td></tr></table> + #rdpStyleMap + + + relativeToGround + + + relativeToGround + -5.7166666667,57.8333333333,1524.0 -6.2769444444,57.7875,1524.0 -6.2511111111,57.0,1524.0 -5.9455555556,57.0,1524.0 -5.9608333333,57.6444444444,1524.0 -5.6805555556,57.6677777778,1524.0 -5.7166666667,57.8333333333,1524.0 + + + + + relativeToGround + + + relativeToGround + -5.7166666667,57.8333333333,228.60000000000002 -6.2769444444,57.7875,228.60000000000002 -6.2511111111,57.0,228.60000000000002 -5.9455555556,57.0,228.60000000000002 -5.9608333333,57.6444444444,228.60000000000002 -5.6805555556,57.6677777778,228.60000000000002 -5.7166666667,57.8333333333,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -5.7166666667,57.8333333333,228.60000000000002 -6.2769444444,57.7875,228.60000000000002 -6.2769444444,57.7875,1524.0 -5.7166666667,57.8333333333,1524.0 -5.7166666667,57.8333333333,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -6.2769444444,57.7875,228.60000000000002 -6.2511111111,57.0,228.60000000000002 -6.2511111111,57.0,1524.0 -6.2769444444,57.7875,1524.0 -6.2769444444,57.7875,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -6.2511111111,57.0,228.60000000000002 -5.9455555556,57.0,228.60000000000002 -5.9455555556,57.0,1524.0 -6.2511111111,57.0,1524.0 -6.2511111111,57.0,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -5.9455555556,57.0,228.60000000000002 -5.9608333333,57.6444444444,228.60000000000002 -5.9608333333,57.6444444444,1524.0 -5.9455555556,57.0,1524.0 -5.9455555556,57.0,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -5.9608333333,57.6444444444,228.60000000000002 -5.6805555556,57.6677777778,228.60000000000002 -5.6805555556,57.6677777778,1524.0 -5.9608333333,57.6444444444,1524.0 -5.9608333333,57.6444444444,228.60000000000002 + + + + + relativeToGround + + + relativeToGround + -5.6805555556,57.6677777778,228.60000000000002 -5.7166666667,57.8333333333,228.60000000000002 -5.7166666667,57.8333333333,1524.0 -5.6805555556,57.6677777778,1524.0 -5.6805555556,57.6677777778,228.60000000000002 + + + + + + + EGR610C THE HIGHLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="1671" txt_name="THE HIGHLANDS"><tr><td>582218N 0033224W -<br/>581434N 0031929W -<br/>581121N 0032654W -<br/>581900N 0033940W -<br/>582218N 0033224W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.<br/><br/>In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.<br/><br/>Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.<br/><br/>New SI issued on activation.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.54,58.3716666667,609.6 -3.6611111111,58.3166666667,609.6 -3.4483333333,58.1891666667,609.6 -3.3247222222,58.2427777778,609.6 -3.54,58.3716666667,609.6 + + + + + + EGR610D THE HIGHLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="1672" txt_name="THE HIGHLANDS"><tr><td>574900N 0040606W -<br/>574500N 0040254W -<br/>574234N 0041056W -<br/>573900N 0043000W -<br/>574700N 0042500W -<br/>574900N 0040606W <br/>Upper limit: 2000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.<br/><br/>In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.<br/><br/>Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.<br/><br/>New SI issued on activation.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1016666667,57.8166666667,609.6 -4.4166666667,57.7833333333,609.6 -4.5,57.65,609.6 -4.1822222222,57.7094444444,609.6 -4.0483333333,57.75,609.6 -4.1016666667,57.8166666667,609.6 + + + + + + EGR704 BALMORAL + <table border="1" cellpadding="1" cellspacing="0" row_id="4854" txt_name="BALMORAL"><tr><td>A circle, 1 NM radius, centred at 570227N 0031349W <br/>Upper limit: 3500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>Any aircraft operated by or on behalf of Police Scotland;<br/>any aircraft operated by or on behalf of the Scottish Air Ambulance Service;<br/>any aircraft operated by or on behalf of the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;<br/>any aircraft operated by or on behalf of The King's Helicopter Flight;<br/>any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —<br/><br/>Operated by a member of the Royal Family, or landing in the grounds of Balmoral at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.<br/><br/>SI 2019/1321.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2302777778,57.0574639676,1066.8 -3.2347217264,57.0572866625,1066.8 -3.2390708352,57.0567585311,1066.8 -3.2432322962,57.0558908441,1066.8 -3.2471173212,57.0547021176,1066.8 -3.250643042,57.0532177164,1066.8 -3.2537342822,57.0514693109,1066.8 -3.2563251621,57.0494941996,1066.8 -3.2583605024,57.0473345108,1066.8 -3.2597969969,57.0450363023,1066.8 -3.260604129,57.0426485773,1066.8 -3.2607648138,57.0402222381,1066.8 -3.2602757524,57.0378090004,1066.8 -3.2591474911,57.0354602907,1066.8 -3.2574041866,57.033226151,1066.8 -3.2550830817,57.0311541735,1066.8 -3.2522337042,57.0292884884,1066.8 -3.2489168064,57.027668826,1066.8 -3.2452030682,57.0263296728,1066.8 -3.2411715924,57.025299539,1066.8 -3.2369082222,57.0246003539,1066.8 -3.232503719,57.0242470008,1066.8 -3.2280518366,57.0242470008,1066.8 -3.2236473334,57.0246003539,1066.8 -3.2193839632,57.025299539,1066.8 -3.2153524873,57.0263296728,1066.8 -3.2116387492,57.027668826,1066.8 -3.2083218513,57.0292884884,1066.8 -3.2054724739,57.0311541735,1066.8 -3.203151369,57.033226151,1066.8 -3.2014080645,57.0354602907,1066.8 -3.2002798032,57.0378090004,1066.8 -3.1997907417,57.0402222381,1066.8 -3.1999514266,57.0426485773,1066.8 -3.2007585587,57.0450363023,1066.8 -3.2021950531,57.0473345108,1066.8 -3.2042303935,57.0494941996,1066.8 -3.2068212734,57.0514693109,1066.8 -3.2099125136,57.0532177164,1066.8 -3.2134382344,57.0547021176,1066.8 -3.2173232594,57.0558908441,1066.8 -3.2214847204,57.0567585311,1066.8 -3.2258338292,57.0572866625,1066.8 -3.2302777778,57.0574639676,1066.8 + + + + + + EGR705 BIRKHALL + <table border="1" cellpadding="1" cellspacing="0" row_id="4734" txt_name="BIRKHALL"><tr><td>A circle, 1 NM radius, centred at 570144N 0030427W <br/>Upper limit: 3500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by:<br/>Any aircraft operated by, or on behalf of, Police Scotland;<br/>any aircraft operated by, or on behalf of, the Scottish Air Ambulance Service;<br/>any aircraft operated by, or on behalf of, the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;<br/>any aircraft operated by, or on behalf of, The King's Helicopter Flight;<br/>any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —<br/><br/>Operated by a member of the Royal Family, <br/>or landing in the grounds of Birkhall at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.<br/><br/>SI 2019/1320.<br/><br/>Contact: Refer to Statutory Instrument.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0741666667,57.0455195551,1066.8 -3.078609189,57.0453422497,1066.8 -3.0829569019,57.0448141174,1066.8 -3.0871170275,57.0439464289,1066.8 -3.0910008059,57.0427577003,1066.8 -3.0945253956,57.0412732965,1066.8 -3.0976156443,57.0395248879,1066.8 -3.1002056935,57.037549773,1066.8 -3.1022403815,57.0353900803,1066.8 -3.1036764159,57.0330918675,1066.8 -3.10448329,57.030704138,1066.8 -3.1046439242,57.0282777942,1066.8 -3.1041550205,57.0258645518,1066.8 -3.1030271218,57.0235158375,1066.8 -3.1012843771,57.0212816933,1066.8 -3.0989640172,57.0192097116,1066.8 -3.0961155538,57.0173440227,1066.8 -3.0927997198,57.0157243569,1066.8 -3.0890871725,57.0143852009,1066.8 -3.0850569891,57.0133550649,1066.8 -3.0807949857,57.0126558784,1066.8 -3.0763918943,57.0123025245,1066.8 -3.071941439,57.0123025245,1066.8 -3.0675383477,57.0126558784,1066.8 -3.0632763442,57.0133550649,1066.8 -3.0592461609,57.0143852009,1066.8 -3.0555336136,57.0157243569,1066.8 -3.0522177795,57.0173440227,1066.8 -3.0493693162,57.0192097116,1066.8 -3.0470489562,57.0212816933,1066.8 -3.0453062115,57.0235158375,1066.8 -3.0441783129,57.0258645518,1066.8 -3.0436894092,57.0282777942,1066.8 -3.0438500434,57.030704138,1066.8 -3.0446569174,57.0330918675,1066.8 -3.0460929518,57.0353900803,1066.8 -3.0481276399,57.037549773,1066.8 -3.050717689,57.0395248879,1066.8 -3.0538079377,57.0412732965,1066.8 -3.0573325274,57.0427577003,1066.8 -3.0612163059,57.0439464289,1066.8 -3.0653764314,57.0448141174,1066.8 -3.0697241443,57.0453422497,1066.8 -3.0741666667,57.0455195551,1066.8 + + + + + + EGRU001A LAND'S END + <table border="1" cellpadding="1" cellspacing="0" row_id="7866" txt_name="LAND'S END"><tr><td>A circle, 2 NM radius, centred at 500610N 0054014W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6705805556,50.1360027382,609.6 -5.6759075942,50.1358261226,609.6 -5.6811780483,50.135298152,609.6 -5.6863359382,50.1344244342,609.6 -5.691326487,50.1332142493,609.6 -5.6960967056,50.1316804503,609.6 -5.7005959583,50.1298393258,609.6 -5.7047765024,50.1277104258,609.6 -5.7085939962,50.1253163537,609.6 -5.7120079707,50.1226825245,609.6 -5.714982258,50.1198368943,609.6 -5.7174853742,50.1168096619,609.6 -5.7194908511,50.1136329477,609.6 -5.7209775143,50.1103404517,609.6 -5.7219297036,50.1069670951,609.6 -5.7223374351,50.1035486495,609.6 -5.7221965023,50.1001213569,609.6 -5.7215085159,50.0967215454,609.6 -5.7202808818,50.0933852444,609.6 -5.7185267176,50.0901478028,609.6 -5.7162647094,50.087043515,609.6 -5.7135189097,50.0841052587,609.6 -5.7103184794,50.0813641471,609.6 -5.7066973762,50.078849201,609.6 -5.7026939937,50.0765870422,609.6 -5.6983507534,50.0746016133,609.6 -5.6937136564,50.0729139251,609.6 -5.6888317968,50.0715418357,609.6 -5.6837568442,50.0704998622,609.6 -5.6785424991,50.0697990282,609.6 -5.6732439281,50.0694467479,609.6 -5.667917183,50.0694467479,609.6 -5.662618612,50.0697990282,609.6 -5.6574042669,50.0704998622,609.6 -5.6523293143,50.0715418357,609.6 -5.6474474547,50.0729139251,609.6 -5.6428103577,50.0746016133,609.6 -5.6384671174,50.0765870422,609.6 -5.6344637349,50.078849201,609.6 -5.6308426317,50.0813641471,609.6 -5.6276422014,50.0841052587,609.6 -5.6248964017,50.087043515,609.6 -5.6226343935,50.0901478028,609.6 -5.6208802293,50.0933852444,609.6 -5.6196525952,50.0967215454,609.6 -5.6189646089,50.1001213569,609.6 -5.6188236761,50.1035486495,609.6 -5.6192314075,50.1069670951,609.6 -5.6201835968,50.1103404517,609.6 -5.62167026,50.1136329477,609.6 -5.6236757369,50.1168096619,609.6 -5.6261788531,50.1198368943,609.6 -5.6291531404,50.1226825245,609.6 -5.6325671149,50.1253163537,609.6 -5.6363846088,50.1277104258,609.6 -5.6405651528,50.1298393258,609.6 -5.6450644055,50.1316804503,609.6 -5.6498346241,50.1332142493,609.6 -5.6548251729,50.1344244342,609.6 -5.6599830628,50.135298152,609.6 -5.6652535169,50.1358261226,609.6 -5.6705805556,50.1360027382,609.6 + + + + + + EGRU001B LAND'S END RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8003" txt_name="LAND'S END RWY 02"><tr><td>500326N 0054128W -<br/>500337N 0054215W -<br/>500426N 0054148W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500414N 0054102W -<br/>500326N 0054128W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6911472222,50.0572722222,609.6 -5.6838163611,50.0705099722,609.6 -5.688277731,50.0714098034,609.6 -5.6925948678,50.072565022,609.6 -5.6967325833,50.0739661944,609.6 -5.7043,50.0602944444,609.6 -5.6911472222,50.0572722222,609.6 + + + + + + EGRU001C LAND'S END RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7512" txt_name="LAND'S END RWY 20"><tr><td>500855N 0053919W -<br/>500845N 0053832W -<br/>500759N 0053857W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500808N 0053945W -<br/>500855N 0053919W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6552638889,50.1487388889,609.6 -5.6625601111,50.135601,609.6 -5.6579724056,50.1350009132,609.6 -5.6534878727,50.1341368825,609.6 -5.6491431944,50.133016,609.6 -5.6420861111,50.1457166667,609.6 -5.6552638889,50.1487388889,609.6 + + + + + + EGRU001D LAND'S END RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7988" txt_name="LAND'S END RWY 07"><tr><td>500441N 0054420W -<br/>500511N 0054441W -<br/>500537N 0054314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500508N 0054254W -<br/>500441N 0054420W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7388095556,50.0781908333,609.6 -5.7148789444,50.0854752222,609.6 -5.7171147379,50.0881153518,609.6 -5.7189715321,50.0908744357,609.6 -5.7204341389,50.09373,609.6 -5.7447753056,50.0863204167,609.6 -5.7388095556,50.0781908333,609.6 + + + + + + EGRU001E LAND'S END RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8163" txt_name="LAND'S END RWY 25"><tr><td>500738N 0053637W -<br/>500708N 0053616W -<br/>500650N 0053718W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500718N 0053741W -<br/>500738N 0053637W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6103814444,50.1271384722,609.6 -5.6281196944,50.1217638889,609.6 -5.6256200098,50.1192229179,609.6 -5.6234872223,50.1165472972,609.6 -5.6217386667,50.1137588611,609.6 -5.6044106111,50.1190089444,609.6 -5.6103814444,50.1271384722,609.6 + + + + + + EGRU001F LAND'S END RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7933" txt_name="LAND'S END RWY 11"><tr><td>500657N 0054430W -<br/>500726N 0054411W -<br/>500707N 0054258W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500637N 0054316W -<br/>500657N 0054430W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7417068611,50.1157045,609.6 -5.7210458611,50.1101511389,609.6 -5.7197968384,50.1130486781,609.6 -5.7181462876,50.1158619309,609.6 -5.7161076111,50.1185679444,609.6 -5.7363042222,50.1239965556,609.6 -5.7417068611,50.1157045,609.6 + + + + + + EGRU001G LAND'S END RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7957" txt_name="LAND'S END RWY 29"><tr><td>500516N 0053607W -<br/>500446N 0053627W -<br/>500505N 0053737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500535N 0053716W -<br/>500516N 0053607W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6019960278,50.0878068333,609.6 -5.6210773611,50.0929611389,609.6 -5.6226464125,50.0901288342,609.6 -5.6246059681,50.087399098,609.6 -5.62694,50.0847941667,609.6 -5.6073946111,50.0795147222,609.6 -5.6019960278,50.0878068333,609.6 + + + + + + EGRU001H LAND'S END RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="8074" txt_name="LAND'S END RWY 16"><tr><td>500843N 0054216W -<br/>500855N 0054130W -<br/>500806N 0054059W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500754N 0054146W -<br/>500843N 0054216W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.704525,50.1452111111,609.6 -5.6961072222,50.1316766111,609.6 -5.6919400848,50.1330387019,609.6 -5.6875986663,50.1341536005,609.6 -5.6831183889,50.1350122222,609.6 -5.6915305556,50.1485444444,609.6 -5.704525,50.1452111111,609.6 + + + + + + EGRU001I LAND'S END RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="7559" txt_name="LAND'S END RWY 34"><tr><td>500334N 0053810W -<br/>500322N 0053857W -<br/>500413N 0053929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to<br/>500425N 0053842W -<br/>500334N 0053810W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.636175,50.0593444444,609.6 -5.6450833611,50.0737236667,609.6 -5.649245904,50.0723633887,609.6 -5.653581799,50.0712499565,609.6 -5.6580558056,50.0703924167,609.6 -5.6491416667,50.0560111111,609.6 -5.636175,50.0593444444,609.6 + + + + + + EGRU002A PENZANCE + <table border="1" cellpadding="1" cellspacing="0" row_id="8077" txt_name="PENZANCE"><tr><td>A circle, 2 NM radius, centred at 500749N 0053050W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5139555556,50.1636886897,609.6 -5.5192856706,50.1635120748,609.6 -5.5245591683,50.1629841063,609.6 -5.5297200365,50.1621103922,609.6 -5.5347134667,50.1609002124,609.6 -5.539486439,50.1593664198,609.6 -5.5439882886,50.157525303,609.6 -5.5481712449,50.1553964121,609.6 -5.5519909409,50.1530023503,609.6 -5.555406884,50.1503685326,609.6 -5.5583828855,50.1475229149,609.6 -5.5608874435,50.1444956961,609.6 -5.5628940747,50.1413189963,609.6 -5.5643815924,50.1380265155,609.6 -5.5653343275,50.1346531747,609.6 -5.5657422906,50.1312347453,609.6 -5.5656012729,50.1278074691,609.6 -5.5649128862,50.1244076743,609.6 -5.5636845407,50.1210713898,609.6 -5.5619293619,50.1178339644,609.6 -5.5596660466,50.1147296924,609.6 -5.5569186613,50.1117914512,609.6 -5.5537163839,50.1090503539,609.6 -5.5500931917,50.106535421,609.6 -5.5460875004,50.1042732742,609.6 -5.541741756,50.1022878559,609.6 -5.5371019861,50.1006001768,609.6 -5.532217313,50.0992280948,609.6 -5.5271394359,50.098186127,609.6 -5.5219220864,50.0974852968,609.6 -5.5166204626,50.0971330184,609.6 -5.5112906485,50.0971330184,609.6 -5.5059890247,50.0974852968,609.6 -5.5007716752,50.098186127,609.6 -5.4956937982,50.0992280948,609.6 -5.490809125,50.1006001768,609.6 -5.4861693551,50.1022878559,609.6 -5.4818236107,50.1042732742,609.6 -5.4778179194,50.106535421,609.6 -5.4741947272,50.1090503539,609.6 -5.4709924498,50.1117914512,609.6 -5.4682450646,50.1147296924,609.6 -5.4659817493,50.1178339644,609.6 -5.4642265704,50.1210713898,609.6 -5.4629982249,50.1244076743,609.6 -5.4623098382,50.1278074691,609.6 -5.4621688205,50.1312347453,609.6 -5.4625767836,50.1346531747,609.6 -5.4635295187,50.1380265155,609.6 -5.4650170364,50.1413189963,609.6 -5.4670236676,50.1444956961,609.6 -5.4695282256,50.1475229149,609.6 -5.4725042271,50.1503685326,609.6 -5.4759201702,50.1530023503,609.6 -5.4797398662,50.1553964121,609.6 -5.4839228226,50.157525303,609.6 -5.4884246721,50.1593664198,609.6 -5.4931976444,50.1609002124,609.6 -5.4981910746,50.1621103922,609.6 -5.5033519428,50.1629841063,609.6 -5.5086254405,50.1635120748,609.6 -5.5139555556,50.1636886897,609.6 + + + + + + EGRU002B PENZANCE RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7884" txt_name="PENZANCE RWY 08"><tr><td>500706N 0053454W -<br/>500738N 0053503W -<br/>500745N 0053357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to<br/>500713N 0053348W -<br/>500706N 0053454W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5817965278,50.118266,609.6 -5.5633322778,50.1203276389,609.6 -5.5645434783,50.1232299001,609.6 -5.5653429327,50.1261905351,609.6 -5.5657240556,50.1291854444,609.6 -5.58417825,50.1271248889,609.6 -5.5817965278,50.118266,609.6 + + + + + + EGRU002C PENZANCE RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7620" txt_name="PENZANCE RWY 26"><tr><td>500833N 0052646W -<br/>500801N 0052637W -<br/>500754N 0052744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to<br/>500826N 0052752W -<br/>500833N 0052646W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.4460903889,50.1424680556,609.6 -5.46455675,50.1404263056,609.6 -5.4633515891,50.1375229498,609.6 -5.4625586488,50.1345615865,609.6 -5.4621843333,50.1315663333,609.6 -5.4437078889,50.1336091944,609.6 -5.4460903889,50.1424680556,609.6 + + + + + + EGRU003A CULDROSE + <table border="1" cellpadding="1" cellspacing="0" row_id="7942" txt_name="CULDROSE"><tr><td>A circle, 2.5 NM radius, centred at 500507N 0051515W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2540722222,50.1270222675,609.6 -5.2600465019,50.1268445494,609.6 -5.2659696794,50.1263129153,609.6 -5.271791093,50.1254319124,609.6 -5.2774609581,50.124209076,609.6 -5.282930796,50.1226548643,609.6 -5.2881538508,50.1207825685,609.6 -5.293085492,50.1186081982,609.6 -5.2976835968,50.1161503437,609.6 -5.3019089119,50.1134300161,609.6 -5.3057253884,50.1104704664,609.6 -5.3091004903,50.1072969857,609.6 -5.3120054703,50.1039366885,609.6 -5.3144156139,50.1004182793,609.6 -5.3163104478,50.0967718071,609.6 -5.3176739117,50.0930284076,609.6 -5.3184944912,50.0892200368,609.6 -5.3187653125,50.0853791979,609.6 -5.3184841965,50.0815386634,609.6 -5.3176536728,50.0777311953,609.6 -5.316280954,50.073989266,609.6 -5.3143778694,50.0703447816,609.6 -5.3119607606,50.06682881,609.6 -5.3090503379,50.0634713172,609.6 -5.3056715012,50.0603009122,609.6 -5.3018531249,50.0573446048,609.6 -5.2976278098,50.0546275756,609.6 -5.2930316047,50.0521729635,609.6 -5.2881036984,50.0500016689,609.6 -5.2828860862,50.0481321775,609.6 -5.2774232136,50.0465804034,609.6 -5.271761599,50.0453595547,609.6 -5.2659494404,50.0444800221,609.6 -5.2600362071,50.0439492907,609.6 -5.2540722222,50.0437718769,609.6 -5.2481082373,50.0439492907,609.6 -5.242195004,50.0444800221,609.6 -5.2363828454,50.0453595547,609.6 -5.2307212309,50.0465804034,609.6 -5.2252583582,50.0481321775,609.6 -5.220040746,50.0500016689,609.6 -5.2151128397,50.0521729635,609.6 -5.2105166346,50.0546275756,609.6 -5.2062913196,50.0573446048,609.6 -5.2024729432,50.0603009122,609.6 -5.1990941066,50.0634713172,609.6 -5.1961836839,50.06682881,609.6 -5.193766575,50.0703447816,609.6 -5.1918634905,50.073989266,609.6 -5.1904907716,50.0777311953,609.6 -5.1896602479,50.0815386634,609.6 -5.1893791319,50.0853791979,609.6 -5.1896499532,50.0892200368,609.6 -5.1904705327,50.0930284076,609.6 -5.1918339966,50.0967718071,609.6 -5.1937288306,50.1004182793,609.6 -5.1961389742,50.1039366885,609.6 -5.1990439541,50.1072969857,609.6 -5.202419056,50.1104704664,609.6 -5.2062355326,50.1134300161,609.6 -5.2104608476,50.1161503437,609.6 -5.2150589524,50.1186081982,609.6 -5.2199905936,50.1207825685,609.6 -5.2252136485,50.1226548643,609.6 -5.2306834863,50.124209076,609.6 -5.2363533515,50.1254319124,609.6 -5.2421747651,50.1263129153,609.6 -5.2480979426,50.1268445494,609.6 -5.2540722222,50.1270222675,609.6 + + + + + + EGRU003B CULDROSE RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7525" txt_name="CULDROSE RWY 06"><tr><td>500339N 0051921W -<br/>500408N 0051944W -<br/>500423N 0051857W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500353N 0051837W -<br/>500339N 0051921W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3224722222,50.0608,609.6 -5.3102815833,50.0648040278,609.6 -5.3124470945,50.067469965,609.6 -5.314308046,50.0702295787,609.6 -5.3158546667,50.0730684722,609.6 -5.3288083333,50.0688138889,609.6 -5.3224722222,50.0608,609.6 + + + + + + EGRU003C CULDROSE RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7837" txt_name="CULDROSE RWY 24"><tr><td>500650N 0051129W -<br/>500621N 0051106W -<br/>500609N 0051142W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500637N 0051208W -<br/>500650N 0051129W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.1913138889,50.1138611111,609.6 -5.2022176389,50.11029775,609.6 -5.1995584017,50.1078233936,609.6 -5.1971842309,50.1052319388,609.6 -5.1951074722,50.1025369444,609.6 -5.1849694444,50.10585,609.6 -5.1913138889,50.1138611111,609.6 + + + + + + EGRU003D CULDROSE RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="8189" txt_name="CULDROSE RWY 11"><tr><td>500607N 0051959W -<br/>500637N 0051939W -<br/>500620N 0051838W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500550N 0051858W -<br/>500607N 0051959W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3329861111,50.1018638889,609.6 -5.3160738056,50.0972953889,609.6 -5.3145814639,50.1001392694,609.6 -5.3127741935,50.1029065511,609.6 -5.3106613611,50.1055828333,609.6 -5.3275583333,50.1101472222,609.6 -5.3329861111,50.1018638889,609.6 + + + + + + EGRU003E CULDROSE RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7862" txt_name="CULDROSE RWY 29"><tr><td>500408N 0051031W -<br/>500338N 0051050W -<br/>500355N 0051151W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500424N 0051132W -<br/>500408N 0051031W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.1752277778,50.0688777778,609.6 -5.19210275,50.0734629167,609.6 -5.1936019857,50.0706204565,609.6 -5.1954154024,50.0678548986,609.6 -5.1975335278,50.0651806111,609.6 -5.1806444444,50.0605916667,609.6 -5.1752277778,50.0688777778,609.6 + + + + + + EGRU003F CULDROSE RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7777" txt_name="CULDROSE RWY 18"><tr><td>500805N 0051538W -<br/>500806N 0051448W -<br/>500736N 0051447W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500737N 0051537W -<br/>500805N 0051538W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2606666667,50.1348166667,609.6 -5.26033425,50.1268269722,609.6 -5.2556702386,50.1270095639,609.6 -5.2509978848,50.1269752666,609.6 -5.2463415833,50.12672425,609.6 -5.2466861111,50.1350555556,609.6 -5.2606666667,50.1348166667,609.6 + + + + + + EGRU003G CULDROSE RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7851" txt_name="CULDROSE RWY 36"><tr><td>500209N 0051433W -<br/>500208N 0051524W -<br/>500238N 0051525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to<br/>500240N 0051435W -<br/>500209N 0051433W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2425861111,50.0357222222,609.6 -5.2429433056,50.0443929444,609.6 -5.2475654006,50.0439831503,609.6 -5.2522213076,50.0437889397,609.6 -5.2568868333,50.0438113333,609.6 -5.2565416667,50.0354833333,609.6 -5.2425861111,50.0357222222,609.6 + + + + + + EGRU004A PREDANNACK + <table border="1" cellpadding="1" cellspacing="0" row_id="7751" txt_name="PREDANNACK"><tr><td>A circle, 2 NM radius, centred at 500007N 0051354W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2317694444,50.0353338744,609.6 -5.2370853375,50.0351572562,609.6 -5.2423447648,50.0346292776,609.6 -5.2474918642,50.0337555467,609.6 -5.2524719738,50.0325453435,609.6 -5.2572322156,50.0310115211,609.6 -5.2617220602,50.0291703683,609.6 -5.2658938646,50.0270414353,609.6 -5.2697033803,50.0246473257,609.6 -5.2731102226,50.0220134548,609.6 -5.2760782991,50.0191677788,609.6 -5.2785761915,50.0161404971,609.6 -5.2805774868,50.0129637305,609.6 -5.2820610542,50.0096711794,609.6 -5.2830112659,50.0062977655,609.6 -5.2834181582,50.0028792609,609.6 -5.283277533,49.9994519082,609.6 -5.2825909971,49.9960520364,609.6 -5.2813659402,49.9927156753,609.6 -5.2796154522,49.9894781746,609.6 -5.2773581795,49.9863738295,609.6 -5.2746181242,49.9834355182,609.6 -5.2714243858,49.9806943547,609.6 -5.2678108511,49.9781793605,609.6 -5.2638158332,49.9759171581,609.6 -5.2594816653,49.9739316906,609.6 -5.2548542522,49.9722439694,609.6 -5.2499825859,49.9708718529,609.6 -5.2449182283,49.9698298588,609.6 -5.2397147684,49.9691290109,609.6 -5.2344272576,49.9687767236,609.6 -5.2291116313,49.9687767236,609.6 -5.2238241205,49.9691290109,609.6 -5.2186206606,49.9698298588,609.6 -5.213556303,49.9708718529,609.6 -5.2086846367,49.9722439694,609.6 -5.2040572236,49.9739316906,609.6 -5.1997230557,49.9759171581,609.6 -5.1957280378,49.9781793605,609.6 -5.1921145031,49.9806943547,609.6 -5.1889207647,49.9834355182,609.6 -5.1861807094,49.9863738295,609.6 -5.1839234367,49.9894781746,609.6 -5.1821729487,49.9927156753,609.6 -5.1809478918,49.9960520364,609.6 -5.1802613559,49.9994519082,609.6 -5.1801207307,50.0028792609,609.6 -5.180527623,50.0062977655,609.6 -5.1814778347,50.0096711794,609.6 -5.1829614021,50.0129637305,609.6 -5.1849626974,50.0161404971,609.6 -5.1874605898,50.0191677788,609.6 -5.1904286663,50.0220134548,609.6 -5.1938355086,50.0246473257,609.6 -5.1976450242,50.0270414353,609.6 -5.2018168287,50.0291703683,609.6 -5.2063066733,50.0310115211,609.6 -5.2110669151,50.0325453435,609.6 -5.2160470246,50.0337555467,609.6 -5.221194124,50.0346292776,609.6 -5.2264535514,50.0351572562,609.6 -5.2317694444,50.0353338744,609.6 + + + + + + EGRU004B PREDANNACK RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7945" txt_name="PREDANNACK RWY 05"><tr><td>495742N 0051701W -<br/>495805N 0051736W -<br/>495854N 0051622W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>495831N 0051546W -<br/>495742N 0051701W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2835419444,49.9617730833,609.6 -5.2627449167,49.9753855556,609.6 -5.2663444516,49.9772937977,609.6 -5.2696628728,49.979403434,609.6 -5.2726731667,49.9816973056,609.6 -5.2934640556,49.9680870278,609.6 -5.2835419444,49.9617730833,609.6 + + + + + + EGRU004C PREDANNACK RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7728" txt_name="PREDANNACK RWY 23"><tr><td>500232N 0051048W -<br/>500209N 0051012W -<br/>500121N 0051127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>500143N 0051203W -<br/>500232N 0051048W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.1799270833,50.0422724167,609.6 -5.2007712222,50.0286782778,609.6 -5.1971696359,50.0267686512,609.6 -5.1938502156,50.024657554,609.6 -5.19084,50.0223621944,609.6 -5.1699896944,50.0359585278,609.6 -5.1799270833,50.0422724167,609.6 + + + + + + EGRU004D PREDANNACK RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7533" txt_name="PREDANNACK RWY 09"><tr><td>495940N 0051842W -<br/>500013N 0051843W -<br/>500013N 0051700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>495940N 0051656W -<br/>495940N 0051842W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3117936944,49.9944973611,609.6 -5.2821116389,49.9945571944,609.6 -5.2829561989,49.9975243578,609.6 -5.2833808119,50.0005286115,609.6 -5.2833819167,50.0035453056,609.6 -5.3118256944,50.0034878056,609.6 -5.3117936944,49.9944973611,609.6 + + + + + + EGRU004E PREDANNACK RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7925" txt_name="PREDANNACK RWY 27"><tr><td>500013N 0050926W -<br/>495941N 0050926W -<br/>495941N 0051053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>500013N 0051049W -<br/>500013N 0050926W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.1573170556,50.00371625,609.6 -5.180168,50.0036954167,609.6 -5.1801480057,50.0006787566,609.6 -5.1805515819,49.9976733054,609.6 -5.1813753611,49.9947037222,609.6 -5.1572850556,49.9947258056,609.6 -5.1573170556,50.00371625,609.6 + + + + + + EGRU004F PREDANNACK RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="8082" txt_name="PREDANNACK RWY 13"><tr><td>500131N 0051744W -<br/>500157N 0051713W -<br/>500127N 0051613W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>500100N 0051641W -<br/>500131N 0051744W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2954350278,50.0253619444,609.6 -5.2780854722,50.0167982778,609.6 -5.2758280709,50.0194338016,609.6 -5.2732102702,50.0219271581,609.6 -5.2702534167,50.0242579444,609.6 -5.2869394444,50.0324947222,609.6 -5.2954350278,50.0253619444,609.6 + + + + + + EGRU004G PREDANNACK RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="7917" txt_name="PREDANNACK RWY 31"><tr><td>495826N 0051006W -<br/>495800N 0051037W -<br/>495837N 0051152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>495902N 0051119W -<br/>495826N 0051006W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.1683617778,49.9738475,609.6 -5.1885124444,49.9838324444,609.6 -5.1912391424,49.9813889971,609.6 -5.1942966282,49.9791142377,609.6 -5.1976598889,49.9770267222,609.6 -5.1768470278,49.9667146667,609.6 -5.1683617778,49.9738475,609.6 + + + + + + EGRU004H PREDANNACK RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7985" txt_name="PREDANNACK RWY 18"><tr><td>500307N 0051420W -<br/>500308N 0051330W -<br/>500206N 0051328W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>500206N 0051419W -<br/>500307N 0051420W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2389025278,50.0520801944,609.6 -5.2384789167,50.0350520833,609.6 -5.2338293861,50.035307421,609.6 -5.2291630406,50.0352915093,609.6 -5.2245179722,50.0350044722,609.6 -5.2249413611,50.0522232222,609.6 -5.2389025278,50.0520801944,609.6 + + + + + + EGRU004I PREDANNACK RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7574" txt_name="PREDANNACK RWY 36"><tr><td>495707N 0051321W -<br/>495706N 0051411W -<br/>495808N 0051413W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to<br/>495809N 0051322W -<br/>495707N 0051321W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.2224781111,49.9518661389,609.6 -5.2229034722,49.9692269444,609.6 -5.2275257288,49.9688452124,609.6 -5.2321824878,49.9687336718,609.6 -5.2368358889,49.9688932222,609.6 -5.23641025,49.9517231111,609.6 -5.2224781111,49.9518661389,609.6 + + + + + + EGRU005A NEWQUAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7664" txt_name="NEWQUAY"><tr><td>A circle, 2.5 NM radius, centred at 502627N 0045943W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.995375,50.4823974866,609.6 -5.0013939644,50.4822197775,609.6 -5.0073614427,50.4816881703,609.6 -5.0132263927,50.4808072122,609.6 -5.0189386559,50.4795844382,609.6 -5.0244493897,50.4780303064,609.6 -5.0297114877,50.4761581077,609.6 -5.0346799846,50.4739838514,609.6 -5.0393124424,50.4715261273,609.6 -5.0435693141,50.4688059458,609.6 -5.0474142818,50.4658465572,609.6 -5.0508145666,50.462673252,609.6 -5.0537412075,50.4593131434,609.6 -5.0561693067,50.4557949349,609.6 -5.0580782394,50.4521486742,609.6 -5.0594518272,50.4484054954,609.6 -5.0602784716,50.4445973531,609.6 -5.0605512498,50.4407567484,609.6 -5.0602679685,50.4369164519,609.6 -5.0594311786,50.4331092237,609.6 -5.0580481486,50.4293675339,609.6 -5.0561307983,50.4257232862,609.6 -5.0536955929,50.4222075464,609.6 -5.0507633991,50.4188502779,609.6 -5.0473593039,50.4156800876,609.6 -5.043512398,50.4127239826,609.6 -5.0392555263,50.4100071416,609.6 -5.0346250067,50.4075527011,609.6 -5.0296603202,50.4053815597,609.6 -5.024403775,50.4035122011,609.6 -5.0189001474,50.401960538,609.6 -5.0131963018,50.4007397771,609.6 -5.0073407941,50.3998603079,609.6 -5.0013834612,50.3993296149,609.6 -4.995375,50.399152214,609.6 -4.9893665388,50.3993296149,609.6 -4.9834092059,50.3998603079,609.6 -4.9775536982,50.4007397771,609.6 -4.9718498526,50.401960538,609.6 -4.966346225,50.4035122011,609.6 -4.9610896798,50.4053815597,609.6 -4.9561249933,50.4075527011,609.6 -4.9514944737,50.4100071416,609.6 -4.947237602,50.4127239826,609.6 -4.9433906961,50.4156800876,609.6 -4.9399866009,50.4188502779,609.6 -4.9370544071,50.4222075464,609.6 -4.9346192017,50.4257232862,609.6 -4.9327018514,50.4293675339,609.6 -4.9313188214,50.4331092237,609.6 -4.9304820315,50.4369164519,609.6 -4.9301987502,50.4407567484,609.6 -4.9304715284,50.4445973531,609.6 -4.9312981728,50.4484054954,609.6 -4.9326717606,50.4521486742,609.6 -4.9345806933,50.4557949349,609.6 -4.9370087925,50.4593131434,609.6 -4.9399354334,50.462673252,609.6 -4.9433357182,50.4658465572,609.6 -4.9471806859,50.4688059458,609.6 -4.9514375576,50.4715261273,609.6 -4.9560700154,50.4739838514,609.6 -4.9610385123,50.4761581077,609.6 -4.9663006103,50.4780303064,609.6 -4.9718113441,50.4795844382,609.6 -4.9775236073,50.4808072122,609.6 -4.9833885573,50.4816881703,609.6 -4.9893560356,50.4822197775,609.6 -4.995375,50.4823974866,609.6 + + + + + + EGRU005B NEWQUAY RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="7786" txt_name="NEWQUAY RWY 12"><tr><td>502758N 0050435W -<br/>502825N 0050409W -<br/>502756N 0050252W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to<br/>502728N 0050317W -<br/>502758N 0050435W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0762666667,50.4659722222,609.6 -5.0547863333,50.4579050556,609.6 -5.0526992207,50.4605952669,609.6 -5.0503135172,50.4631823971,609.6 -5.0476416111,50.4656529722,609.6 -5.0691111111,50.4737166667,609.6 -5.0762666667,50.4659722222,609.6 + + + + + + EGRU005C NEWQUAY RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="7944" txt_name="NEWQUAY RWY 30"><tr><td>502501N 0045506W -<br/>502433N 0045531W -<br/>502457N 0045635W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to<br/>502525N 0045610W -<br/>502501N 0045506W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9182166667,50.4169,609.6 -4.9360059167,50.4236155278,609.6 -4.9380977536,50.4209275579,609.6 -4.9404871378,50.4183428509,609.6 -4.9431616111,50.4158748333,609.6 -4.9253611111,50.4091555556,609.6 -4.9182166667,50.4169,609.6 + + + + + + EGRU006A EXETER + <table border="1" cellpadding="1" cellspacing="0" row_id="8149" txt_name="EXETER"><tr><td>A circle, 2.5 NM radius, centred at 504403N 0032450W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4138111111,50.7759120447,609.6 -3.4198676675,50.775734343,609.6 -3.4258724149,50.7752027579,609.6 -3.4317739908,50.7743218365,609.6 -3.4375219223,50.7730991138,609.6 -3.4430670607,50.7715450477,609.6 -3.4483620045,50.7696729288,609.6 -3.4533615069,50.7674987661,609.6 -3.4580228647,50.7650411491,609.6 -3.4623062837,50.7623210878,609.6 -3.4661752198,50.7593618318,609.6 -3.4695966899,50.7561886708,609.6 -3.4725415531,50.7528287174,609.6 -3.4749847572,50.7493106742,609.6 -3.4769055504,50.7456645876,609.6 -3.4782876544,50.7419215906,609.6 -3.4791194006,50.7381136364,609.6 -3.4793938246,50.7342732247,609.6 -3.4791087213,50.7304331244,609.6 -3.4782666594,50.726626094,609.6 -3.4768749545,50.7228846017,609.6 -3.4749456026,50.7192405493,609.6 -3.4724951729,50.7157250007,609.6 -3.4695446637,50.7123679174,609.6 -3.4661193192,50.7091979042,609.6 -3.4622484124,50.7062419664,609.6 -3.4579649933,50.7035252806,609.6 -3.4533056062,50.7010709818,609.6 -3.4483099782,50.6988999669,609.6 -3.4430206805,50.6970307181,609.6 -3.4374827676,50.6954791466,609.6 -3.4317433949,50.6942584582,609.6 -3.4258514198,50.6933790415,609.6 -3.4198569881,50.6928483801,609.6 -3.4138111111,50.6926709899,609.6 -3.4077652341,50.6928483801,609.6 -3.4017708025,50.6933790415,609.6 -3.3958788273,50.6942584582,609.6 -3.3901394546,50.6954791466,609.6 -3.3846015417,50.6970307181,609.6 -3.379312244,50.6988999669,609.6 -3.374316616,50.7010709818,609.6 -3.3696572289,50.7035252806,609.6 -3.3653738098,50.7062419664,609.6 -3.361502903,50.7091979042,609.6 -3.3580775585,50.7123679174,609.6 -3.3551270493,50.7157250007,609.6 -3.3526766197,50.7192405493,609.6 -3.3507472677,50.7228846017,609.6 -3.3493555629,50.726626094,609.6 -3.348513501,50.7304331244,609.6 -3.3482283977,50.7342732247,609.6 -3.3485028216,50.7381136364,609.6 -3.3493345678,50.7419215906,609.6 -3.3507166719,50.7456645876,609.6 -3.352637465,50.7493106742,609.6 -3.3550806691,50.7528287174,609.6 -3.3580255323,50.7561886708,609.6 -3.3614470024,50.7593618318,609.6 -3.3653159385,50.7623210878,609.6 -3.3695993576,50.7650411491,609.6 -3.3742607153,50.7674987661,609.6 -3.3792602178,50.7696729288,609.6 -3.3845551615,50.7715450477,609.6 -3.3901002999,50.7730991138,609.6 -3.3958482314,50.7743218365,609.6 -3.4017498073,50.7752027579,609.6 -3.4077545547,50.775734343,609.6 -3.4138111111,50.7759120447,609.6 + + + + + + EGRU006B EXETER RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="8135" txt_name="EXETER RWY 08"><tr><td>504301N 0032942W -<br/>504332N 0032954W -<br/>504343N 0032844W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to<br/>504312N 0032831W -<br/>504301N 0032942W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4950583333,50.7169166667,609.6 -3.4754004444,50.7200062778,609.6 -3.4768640098,50.7228603054,609.6 -3.4779999174,50.7257738522,609.6 -3.4788021944,50.7287317778,609.6 -3.4984444444,50.7256444444,609.6 -3.4950583333,50.7169166667,609.6 + + + + + + EGRU006C EXETER RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8064" txt_name="EXETER RWY 26"><tr><td>504506N 0031958W -<br/>504434N 0031946W -<br/>504423N 0032056W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to<br/>504455N 0032108W -<br/>504506N 0031958W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3329055556,50.7515472222,609.6 -3.3521841667,50.7485441667,609.6 -3.3507272916,50.7456883341,609.6 -3.3495987816,50.7427732951,609.6 -3.3488044444,50.7398142222,609.6 -3.3295111111,50.7428194444,609.6 -3.3329055556,50.7515472222,609.6 + + + + + + EGRU007A DUNKESWELL + <table border="1" cellpadding="1" cellspacing="0" row_id="7724" txt_name="DUNKESWELL"><tr><td>A circle, 2 NM radius, centred at 505136N 0031405W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2347222222,50.8932956049,609.6 -3.2401351738,50.8931190092,609.6 -3.2454906252,50.8925910977,609.6 -3.2507316905,50.8917174782,609.6 -3.2558027069,50.8905074303,609.6 -3.2606498284,50.888973806,609.6 -3.2652216011,50.8871328929,609.6 -3.2694695114,50.8850042399,609.6 -3.2733485023,50.8826104486,609.6 -3.2768174528,50.8799769321,609.6 -3.279839613,50.877131644,609.6 -3.2823829938,50.8741047808,609.6 -3.2844207029,50.8709284596,609.6 -3.2859312278,50.8676363769,609.6 -3.2868986599,50.8642634502,609.6 -3.2873128583,50.8608454468,609.6 -3.2871695533,50.8574186042,609.6 -3.2864703856,50.8540192458,609.6 -3.2852228848,50.8506833957,609.6 -3.2834403834,50.8474463977,609.6 -3.2811418721,50.8443425409,609.6 -3.2783517935,50.8414046975,609.6 -3.2750997803,50.8386639756,609.6 -3.2714203384,50.8361493907,609.6 -3.2673524801,50.8338875599,609.6 -3.2629393099,50.8319024213,609.6 -3.2582275683,50.8302149816,609.6 -3.253267138,50.8288430954,609.6 -3.2481105182,50.827801277,609.6 -3.2428122708,50.8271005476,609.6 -3.237428447,50.82674832,609.6 -3.2320159975,50.82674832,609.6 -3.2266321737,50.8271005476,609.6 -3.2213339263,50.827801277,609.6 -3.2161773064,50.8288430954,609.6 -3.2112168762,50.8302149816,609.6 -3.2065051345,50.8319024213,609.6 -3.2020919643,50.8338875599,609.6 -3.198024106,50.8361493907,609.6 -3.1943446642,50.8386639756,609.6 -3.1910926509,50.8414046975,609.6 -3.1883025723,50.8443425409,609.6 -3.186004061,50.8474463977,609.6 -3.1842215597,50.8506833957,609.6 -3.1829740588,50.8540192458,609.6 -3.1822748912,50.8574186042,609.6 -3.1821315861,50.8608454468,609.6 -3.1825457846,50.8642634502,609.6 -3.1835132166,50.8676363769,609.6 -3.1850237416,50.8709284596,609.6 -3.1870614507,50.8741047808,609.6 -3.1896048314,50.877131644,609.6 -3.1926269917,50.8799769321,609.6 -3.1960959421,50.8826104486,609.6 -3.1999749331,50.8850042399,609.6 -3.2042228433,50.8871328929,609.6 -3.208794616,50.888973806,609.6 -3.2136417376,50.8905074303,609.6 -3.2187127539,50.8917174782,609.6 -3.2239538193,50.8925910977,609.6 -3.2293092706,50.8931190092,609.6 -3.2347222222,50.8932956049,609.6 + + + + + + EGRU007B DUNKESWELL RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7790" txt_name="DUNKESWELL RWY 04"><tr><td>504912N 0031650W -<br/>504933N 0031729W -<br/>505017N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to<br/>504956N 0031549W -<br/>504912N 0031650W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2805972222,50.8198666667,609.6 -3.2636403056,50.8321895278,609.6 -3.2674813106,50.8339522696,609.6 -3.2710560959,50.8359269644,609.6 -3.2743355833,50.8380975556,609.6 -3.2912888889,50.825775,609.6 -3.2805972222,50.8198666667,609.6 + + + + + + EGRU007C DUNKESWELL RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7872" txt_name="DUNKESWELL RWY 22"><tr><td>505400N 0031120W -<br/>505339N 0031042W -<br/>505255N 0031142W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to<br/>505316N 0031221W -<br/>505400N 0031120W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1889333333,50.9000361111,609.6 -3.2058049722,50.8878178611,609.6 -3.2019593037,50.886054867,609.6 -3.1983808085,50.8840796765,609.6 -3.1950986389,50.8819083889,609.6 -3.1782222222,50.8941277778,609.6 -3.1889333333,50.9000361111,609.6 + + + + + + EGRU008A MERRYFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="7593" txt_name="MERRYFIELD"><tr><td>A circle, 2.5 NM radius, centred at 505747N 0025620W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9388138889,51.0047548483,609.6 -2.9449001943,51.0045771522,609.6 -2.950934435,51.0040455843,609.6 -2.9568649954,51.0031646914,609.6 -2.9626411535,51.0019420085,609.6 -2.9682135183,51.0003879933,609.6 -2.9735344549,50.9985159364,609.6 -2.9785584938,50.9963418465,609.6 -2.9832427217,50.9938843127,609.6 -2.9875471493,50.9911643446,609.6 -2.9914350528,50.9882051916,609.6 -2.9948732879,50.9850321428,609.6 -2.9978325712,50.9816723101,609.6 -3.0002877285,50.9781543952,609.6 -3.0022179071,50.974508444,609.6 -3.0036067504,50.9707655884,609.6 -3.0044425336,50.9669577805,609.6 -3.0047182595,50.963117519,609.6 -3.004431714,50.9592775715,609.6 -3.0035854798,50.955470695,609.6 -3.0021869098,50.9517293565,609.6 -3.00024806,50.9480854563,609.6 -2.9977855824,50.9445700566,609.6 -2.9948205789,50.9412131175,609.6 -2.9913784186,50.9380432423,609.6 -2.9874885185,50.9350874347,609.6 -2.983184091,50.93237087,609.6 -2.9785018596,50.9299166817,609.6 -2.9734817459,50.9277457654,609.6 -2.9681665295,50.9258766021,609.6 -2.9626014849,50.9243251021,609.6 -2.956833998,50.9231044702,609.6 -2.9509131644,50.9222250943,609.6 -2.9448893748,50.9216944577,609.6 -2.9388138889,50.9215170757,609.6 -2.932738403,50.9216944577,609.6 -2.9267146134,50.9222250943,609.6 -2.9207937798,50.9231044702,609.6 -2.9150262928,50.9243251021,609.6 -2.9094612483,50.9258766021,609.6 -2.9041460319,50.9277457654,609.6 -2.8991259182,50.9299166817,609.6 -2.8944436868,50.93237087,609.6 -2.8901392593,50.9350874347,609.6 -2.8862493592,50.9380432423,609.6 -2.8828071989,50.9412131175,609.6 -2.8798421954,50.9445700566,609.6 -2.8773797178,50.9480854563,609.6 -2.875440868,50.9517293565,609.6 -2.874042298,50.955470695,609.6 -2.8731960637,50.9592775715,609.6 -2.8729095182,50.963117519,609.6 -2.8731852442,50.9669577805,609.6 -2.8740210274,50.9707655884,609.6 -2.8754098707,50.974508444,609.6 -2.8773400493,50.9781543952,609.6 -2.8797952066,50.9816723101,609.6 -2.8827544899,50.9850321428,609.6 -2.886192725,50.9882051916,609.6 -2.8900806285,50.9911643446,609.6 -2.894385056,50.9938843127,609.6 -2.899069284,50.9963418465,609.6 -2.9040933229,50.9985159364,609.6 -2.9094142595,51.0003879933,609.6 -2.9149866243,51.0019420085,609.6 -2.9207627824,51.0031646914,609.6 -2.9266933427,51.0040455843,609.6 -2.9327275835,51.0045771522,609.6 -2.9388138889,51.0047548483,609.6 + + + + + + EGRU008B MERRYFIELD RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7863" txt_name="MERRYFIELD RWY 03"><tr><td>505506N 0025754W -<br/>505519N 0025840W -<br/>505540N 0025825W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>505526N 0025739W -<br/>505506N 0025754W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9648844444,50.9183033056,609.6 -2.9608878056,50.9239230833,609.6 -2.9653039687,50.9250301094,609.6 -2.9695825808,50.9263353435,609.6 -2.9737014167,50.927832,609.6 -2.9778534167,50.9219914444,609.6 -2.9648844444,50.9183033056,609.6 + + + + + + EGRU008C MERRYFIELD RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7723" txt_name="MERRYFIELD RWY 21"><tr><td>510051N 0025444W -<br/>510038N 0025357W -<br/>505958N 0025425W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>510011N 0025512W -<br/>510051N 0025444W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.91223225,51.0141108611,609.6 -2.92012775,51.0030484167,609.6 -2.9156159388,51.0020936564,609.6 -2.9112251741,51.00093597,609.6 -2.9069783611,50.9995813889,609.6 -2.8992376111,51.0104227778,609.6 -2.91223225,51.0141108611,609.6 + + + + + + EGRU008D MERRYFIELD RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7797" txt_name="MERRYFIELD RWY 09"><tr><td>505714N 0030118W -<br/>505746N 0030122W -<br/>505750N 0030017W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>505718N 0030012W -<br/>505714N 0030118W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0216006389,50.9538749444,609.6 -3.0034171389,50.9549248056,609.6 -3.0041882275,50.9578865645,609.6 -3.0046194034,50.9608757179,609.6 -3.0047083611,50.9638767222,609.6 -3.0228821389,50.9628273889,609.6 -3.0216006389,50.9538749444,609.6 + + + + + + EGRU008E MERRYFIELD RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7734" txt_name="MERRYFIELD RWY 27"><tr><td>505820N 0025122W -<br/>505748N 0025117W -<br/>505745N 0025223W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>505817N 0025227W -<br/>505820N 0025122W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8560128611,50.9723541944,609.6 -2.8741930833,50.971328,609.6 -2.8734281588,50.9683656014,609.6 -2.8730034372,50.9653760928,609.6 -2.8729210556,50.9623750278,609.6 -2.8547311111,50.96340175,609.6 -2.8560128611,50.9723541944,609.6 + + + + + + EGRU008F MERRYFIELD RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="8066" txt_name="MERRYFIELD RWY 16"><tr><td>510036N 0025807W -<br/>510047N 0025718W -<br/>510015N 0025702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>510006N 0025751W -<br/>510036N 0025807W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9685856389,51.0101076389,609.6 -2.9641047222,51.0015711389,609.6 -2.9596462924,51.0026227467,609.6 -2.9550791053,51.0034685703,609.6 -2.950427,51.0041041944,609.6 -2.9550573333,51.01293025,609.6 -2.9685856389,51.0101076389,609.6 + + + + + + EGRU008G MERRYFIELD RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="8171" txt_name="MERRYFIELD RWY 34"><tr><td>505508N 0025421W -<br/>505458N 0025510W -<br/>505522N 0025522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to<br/>505533N 0025434W -<br/>505508N 0025421W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9058088333,50.9188734444,609.6 -2.9094674444,50.9258746667,609.6 -2.913795743,50.9246351369,609.6 -2.9182540045,50.9235959522,609.6 -2.9228190556,50.9227625,609.6 -2.9193098333,50.9160507778,609.6 -2.9058088333,50.9188734444,609.6 + + + + + + EGRU009A YEOVIL/WESTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="7618" txt_name="YEOVIL/WESTLAND"><tr><td>505817N 0024035W -<br/>505804N 0023747W thence clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to -<br/>505817N 0024035W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6762913333,50.9714693611,609.6 -2.6813214099,50.9701675861,609.6 -2.6861121821,50.9685455593,609.6 -2.6906126594,50.9666205383,609.6 -2.6947749661,50.9644130177,609.6 -2.6985548452,50.9619464963,609.6 -2.7019121291,50.9592472264,609.6 -2.7048111668,50.9563439325,609.6 -2.7072212013,50.9532675051,609.6 -2.7091166941,50.9500506702,609.6 -2.7104775937,50.9467276407,609.6 -2.7112895447,50.9433337517,609.6 -2.7115440354,50.9399050838,609.6 -2.7112384838,50.9364780797,609.6 -2.7103762595,50.9330891564,609.6 -2.7089666428,50.9297743184,609.6 -2.7070247211,50.9265687754,609.6 -2.7045712243,50.9235065695,609.6 -2.7016323001,50.9206202139,609.6 -2.6982392335,50.917940349,609.6 -2.694428112,50.915495418,609.6 -2.690239441,50.9133113666,609.6 -2.685717713,50.9114113683,609.6 -2.6809109363,50.9098155805,609.6 -2.6758701262,50.908540931,609.6 -2.6706487661,50.9076009399,609.6 -2.6653022429,50.9070055769,609.6 -2.6598872626,50.9067611562,609.6 -2.6544612525,50.90687027,609.6 -2.6490817564,50.907331761,609.6 -2.6438058276,50.908140735,609.6 -2.6386894283,50.9092886121,609.6 -2.6337868387,50.910763217,609.6 -2.6291500848,50.9125489081,609.6 -2.6248283884,50.9146267417,609.6 -2.6208676465,50.9169746722,609.6 -2.6173099448,50.9195677849,609.6 -2.614193111,50.922378559,609.6 -2.6115503118,50.9253771585,609.6 -2.6094096989,50.928531748,609.6 -2.6077941069,50.9318088292,609.6 -2.6067208071,50.9351735959,609.6 -2.6062013196,50.9385903034,609.6 -2.6062412861,50.9420226471,609.6 -2.6068404051,50.9454341484,609.6 -2.6079924294,50.9487885423,609.6 -2.6096852278,50.9520501632,609.6 -2.6119009088,50.9551843245,609.6 -2.6146160072,50.9581576886,609.6 -2.6178017294,50.9609386219,609.6 -2.6214242569,50.9634975325,609.6 -2.6254451044,50.9658071869,609.6 -2.6298215278,50.967843,609.6 -2.6762913333,50.9714693611,609.6 + + + + + + EGRU009B YEOVIL/WESTLAND RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8069" txt_name="YEOVIL/WESTLAND RWY 09"><tr><td>505614N 0024415W -<br/>505646N 0024414W -<br/>505644N 0024239W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to<br/>505612N 0024241W -<br/>505614N 0024415W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7375611111,50.9371277778,609.6 -2.7112603056,50.9366077222,609.6 -2.7115396944,50.9396068368,609.6 -2.7113901,50.9426096531,609.6 -2.7108126389,50.9455917222,609.6 -2.7371027778,50.9461111111,609.6 -2.7375611111,50.9371277778,609.6 + + + + + + EGRU009C YEOVIL/WESTLAND RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="8005" txt_name="YEOVIL/WESTLAND RWY 27"><tr><td>505635N 0023449W -<br/>505602N 0023450W -<br/>505604N 0023625W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to<br/>505636N 0023623W -<br/>505635N 0023449W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5801416667,50.9429222222,609.6 -2.6064268056,50.9434709722,609.6 -2.6061537863,50.9404710151,609.6 -2.6063099945,50.9374677222,609.6 -2.6068940556,50.9344855556,609.6 -2.5805972222,50.9339361111,609.6 -2.5801416667,50.9429222222,609.6 + + + + + + EGRU010A COMPTON ABBAS + <table border="1" cellpadding="1" cellspacing="0" row_id="7881" txt_name="COMPTON ABBAS"><tr><td>A circle, 2 NM radius, centred at 505802N 0020913W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1536111111,51.0005172124,609.6 -2.1590365291,51.0003406194,609.6 -2.1644043138,50.9998127162,609.6 -2.1696574483,50.9989391106,609.6 -2.1747401408,50.9977290819,609.6 -2.1795984212,50.9961954822,609.6 -2.1841807168,50.9943545989,609.6 -2.1884384021,50.9922259806,609.6 -2.1923263164,50.9898322288,609.6 -2.1958032439,50.9871987564,609.6 -2.1988323506,50.9843535166,609.6 -2.2013815737,50.9813267053,609.6 -2.2034239597,50.9781504395,609.6 -2.2049379469,50.9748584151,609.6 -2.2059075905,50.9714855491,609.6 -2.2063227271,50.9680676081,609.6 -2.2061790777,50.964640829,609.6 -2.2054782875,50.9612415346,609.6 -2.2042279037,50.9579057482,609.6 -2.2024412905,50.9546688129,609.6 -2.2001374823,50.951565017,609.6 -2.1973409787,50.948627232,609.6 -2.1940814806,50.9458865651,609.6 -2.1903935737,50.9433720314,609.6 -2.1863163598,50.941110247,609.6 -2.1818930427,50.9391251494,609.6 -2.1771704701,50.9374377449,609.6 -2.1721986392,50.9360658874,609.6 -2.1670301693,50.9350240909,609.6 -2.1617197477,50.9343233764,609.6 -2.1563235537,50.9339711562,609.6 -2.1508986685,50.9339711562,609.6 -2.1455024745,50.9343233764,609.6 -2.1401920529,50.9350240909,609.6 -2.135023583,50.9360658874,609.6 -2.1300517522,50.9374377449,609.6 -2.1253291795,50.9391251494,609.6 -2.1209058624,50.941110247,609.6 -2.1168286486,50.9433720314,609.6 -2.1131407416,50.9458865651,609.6 -2.1098812435,50.948627232,609.6 -2.1070847399,50.951565017,609.6 -2.1047809318,50.9546688129,609.6 -2.1029943185,50.9579057482,609.6 -2.1017439347,50.9612415346,609.6 -2.1010431445,50.964640829,609.6 -2.1008994951,50.9680676081,609.6 -2.1013146317,50.9714855491,609.6 -2.1022842754,50.9748584151,609.6 -2.1037982626,50.9781504395,609.6 -2.1058406485,50.9813267053,609.6 -2.1083898716,50.9843535166,609.6 -2.1114189783,50.9871987564,609.6 -2.1148959058,50.9898322288,609.6 -2.1187838201,50.9922259806,609.6 -2.1230415054,50.9943545989,609.6 -2.127623801,50.9961954822,609.6 -2.1324820814,50.9977290819,609.6 -2.137564774,50.9989391106,609.6 -2.1428179084,50.9998127162,609.6 -2.1481856932,51.0003406194,609.6 -2.1536111111,51.0005172124,609.6 + + + + + + EGRU010B COMPTON ABBAS RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="8041" txt_name="COMPTON ABBAS RWY 08"><tr><td>505708N 0021337W -<br/>505739N 0021349W -<br/>505752N 0021222W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to<br/>505720N 0021211W -<br/>505708N 0021337W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2270083333,50.9520972222,609.6 -2.2029971944,50.9555675556,609.6 -2.2044610998,50.9584260794,609.6 -2.2055112153,50.9613562969,609.6 -2.2061389167,50.9643343611,609.6 -2.2301694444,50.9608611111,609.6 -2.2270083333,50.9520972222,609.6 + + + + + + EGRU010C COMPTON ABBAS RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8147" txt_name="COMPTON ABBAS RWY 26"><tr><td>505857N 0020449W -<br/>505825N 0020438W -<br/>505813N 0020604W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to<br/>505844N 0020615W -<br/>505857N 0020449W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0802805556,50.9824361111,609.6 -2.1042831944,50.9789954444,609.6 -2.1028044889,50.9761396879,609.6 -2.1017397236,50.9732113938,609.6 -2.1010975,50.9702344167,609.6 -2.0771138889,50.9736722222,609.6 -2.0802805556,50.9824361111,609.6 + + + + + + EGRU011A BOURNEMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="8083" txt_name="BOURNEMOUTH"><tr><td>A circle, 2.5 NM radius, centred at 504648N 0015033W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8425138889,50.8216839385,609.6 -1.8485763644,50.8215062379,609.6 -1.8545869801,50.8209746562,609.6 -1.860494323,50.8200937406,609.6 -1.8662478708,50.8188710258,609.6 -1.8717984264,50.8173169699,609.6 -1.8770985419,50.8154448635,609.6 -1.8821029264,50.8132707154,609.6 -1.8867688346,50.810813115,609.6 -1.8910564338,50.8080930724,609.6 -1.8949291438,50.805133837,609.6 -1.8983539496,50.8019606985,609.6 -1.901301682,50.7986007693,609.6 -1.9037472645,50.7950827518,609.6 -1.9056699251,50.7914366922,609.6 -1.9070533701,50.7876937236,609.6 -1.9078859195,50.7838857986,609.6 -1.9081606025,50.780045417,609.6 -1.9078752123,50.7762053473,609.6 -1.9070323202,50.7723983477,609.6 -1.9056392495,50.7686568861,609.6 -1.9037080077,50.7650128642,609.6 -1.9012551809,50.7614973454,609.6 -1.8983017878,50.758140291,609.6 -1.8948730975,50.7549703053,609.6 -1.8909984115,50.7520143936,609.6 -1.8867108124,50.7492977321,609.6 -1.88204688,50.7468434554,609.6 -1.87704638,50.7446724602,609.6 -1.8717519253,50.7428032284,609.6 -1.866208614,50.7412516713,609.6 -1.8604636474,50.7400309942,609.6 -1.8545659302,50.7391515856,609.6 -1.8485656572,50.7386209292,609.6 -1.8425138889,50.7384435406,609.6 -1.8364621206,50.7386209292,609.6 -1.8304618475,50.7391515856,609.6 -1.8245641304,50.7400309942,609.6 -1.8188191638,50.7412516713,609.6 -1.8132758525,50.7428032284,609.6 -1.8079813978,50.7446724602,609.6 -1.8029808978,50.7468434554,609.6 -1.7983169654,50.7492977321,609.6 -1.7940293662,50.7520143936,609.6 -1.7901546803,50.7549703053,609.6 -1.78672599,50.758140291,609.6 -1.7837725969,50.7614973454,609.6 -1.78131977,50.7650128642,609.6 -1.7793885283,50.7686568861,609.6 -1.7779954575,50.7723983477,609.6 -1.7771525655,50.7762053473,609.6 -1.7768671752,50.780045417,609.6 -1.7771418583,50.7838857986,609.6 -1.7779744077,50.7876937236,609.6 -1.7793578527,50.7914366922,609.6 -1.7812805133,50.7950827518,609.6 -1.7837260958,50.7986007693,609.6 -1.7866738282,50.8019606985,609.6 -1.790098634,50.805133837,609.6 -1.793971344,50.8080930724,609.6 -1.7982589432,50.810813115,609.6 -1.8029248514,50.8132707154,609.6 -1.8079292359,50.8154448635,609.6 -1.8132293514,50.8173169699,609.6 -1.818779907,50.8188710258,609.6 -1.8245334547,50.8200937406,609.6 -1.8304407977,50.8209746562,609.6 -1.8364514133,50.8215062379,609.6 -1.8425138889,50.8216839385,609.6 + + + + + + EGRU011B BOURNEMOUTH RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="8011" txt_name="BOURNEMOUTH RWY 08"><tr><td>504546N 0015508W -<br/>504617N 0015521W -<br/>504626N 0015427W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to<br/>504555N 0015414W -<br/>504546N 0015508W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9189138889,50.7626972222,609.6 -1.9038303611,50.7652141944,609.6 -1.9053602225,50.768054234,609.6 -1.906563561,50.7709567886,609.6 -1.9074340556,50.7739067778,609.6 -1.9225055556,50.7713916667,609.6 -1.9189138889,50.7626972222,609.6 + + + + + + EGRU011C BOURNEMOUTH RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7614" txt_name="BOURNEMOUTH RWY 26"><tr><td>504754N 0014536W -<br/>504723N 0014523W -<br/>504710N 0014639W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to<br/>504742N 0014652W -<br/>504754N 0014536W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7601111111,50.798375,609.6 -1.7811646111,50.7948912778,609.6 -1.7796401409,50.7920496202,609.6 -1.7784428843,50.7891457046,609.6 -1.7775790278,50.7861946389,609.6 -1.7565111111,50.7896805556,609.6 -1.7601111111,50.798375,609.6 + + + + + + EGRU012A SOUTHAMPTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7914" txt_name="SOUTHAMPTON"><tr><td>A circle, 2 NM radius, centred at 505701N 0012124W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3566666667,50.9835728651,609.6 -1.3620901095,50.9833962716,609.6 -1.3674559401,50.9828683672,609.6 -1.3727071623,50.9819947593,609.6 -1.3777880049,50.9807847276,609.6 -1.3826445173,50.979251124,609.6 -1.3872251457,50.977410236,609.6 -1.3914812822,50.9752816122,609.6 -1.3953677827,50.9728878542,609.6 -1.3988434463,50.9702543748,609.6 -1.4018714524,50.9674091274,609.6 -1.4044197499,50.9643823079,609.6 -1.4064613948,50.9612060334,609.6 -1.4079748335,50.9579139998,609.6 -1.4089441267,50.9545411242,609.6 -1.4093591147,50.9511231733,609.6 -1.4092155198,50.9476963842,609.6 -1.4085149867,50.9442970796,609.6 -1.4072650597,50.9409612832,609.6 -1.4054790979,50.937724338,609.6 -1.403176129,50.9346205324,609.6 -1.4003806434,50.9316827382,609.6 -1.3971223312,50.9289420627,609.6 -1.3934357654,50.9264275208,609.6 -1.3893600339,50.9241657291,609.6 -1.3849383244,50.9221806251,609.6 -1.3802174678,50.920493215,609.6 -1.3752474433,50.919121353,609.6 -1.3700808509,50.918079553,609.6 -1.3647723582,50.9173788361,609.6 -1.3593781241,50.9170266148,609.6 -1.3539552092,50.9170266148,609.6 -1.3485609751,50.9173788361,609.6 -1.3432524824,50.918079553,609.6 -1.3380858901,50.919121353,609.6 -1.3331158655,50.920493215,609.6 -1.3283950089,50.9221806251,609.6 -1.3239732994,50.9241657291,609.6 -1.3198975679,50.9264275208,609.6 -1.3162110021,50.9289420627,609.6 -1.31295269,50.9316827382,609.6 -1.3101572043,50.9346205324,609.6 -1.3078542354,50.937724338,609.6 -1.3060682736,50.9409612832,609.6 -1.3048183467,50.9442970796,609.6 -1.3041178135,50.9476963842,609.6 -1.3039742186,50.9511231733,609.6 -1.3043892067,50.9545411242,609.6 -1.3053584999,50.9579139998,609.6 -1.3068719385,50.9612060334,609.6 -1.3089135835,50.9643823079,609.6 -1.3114618809,50.9674091274,609.6 -1.314489887,50.9702543748,609.6 -1.3179655506,50.9728878542,609.6 -1.3218520511,50.9752816122,609.6 -1.3261081877,50.977410236,609.6 -1.330688816,50.979251124,609.6 -1.3355453284,50.9807847276,609.6 -1.340626171,50.9819947593,609.6 -1.3458773932,50.9828683672,609.6 -1.3512432239,50.9833962716,609.6 -1.3566666667,50.9835728651,609.6 + + + + + + EGRU012B SOUTHAMPTON RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8150" txt_name="SOUTHAMPTON RWY 02"><tr><td>505359N 0012239W -<br/>505410N 0012327W -<br/>505514N 0012251W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to<br/>505504N 0012203W -<br/>505359N 0012239W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3774111111,50.8996805556,609.6 -1.3674003333,50.9176806667,609.6 -1.3720051772,50.9184244585,609.6 -1.3764853887,50.9194274358,609.6 -1.3808045556,50.9206814444,609.6 -1.3908194444,50.9026638889,609.6 -1.3774111111,50.8996805556,609.6 + + + + + + EGRU012C SOUTHAMPTON RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="8169" txt_name="SOUTHAMPTON RWY 20"><tr><td>510004N 0012010W -<br/>505953N 0011921W -<br/>505848N 0011958W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to<br/>505858N 0012046W -<br/>510004N 0012010W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3360194444,51.0010722222,609.6 -1.3461549722,50.9829045278,609.6 -1.3415383674,50.982173002,609.6 -1.3370452143,50.9811815632,609.6 -1.3327121667,50.9799383056,609.6 -1.3225805556,50.9980888889,609.6 -1.3360194444,51.0010722222,609.6 + + + + + + EGRU013A LEE-ON-SOLENT + <table border="1" cellpadding="1" cellspacing="0" row_id="7871" txt_name="LEE-ON-SOLENT"><tr><td>504810N 0010930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to<br/>504824N 0010921W -<br/>505049N 0011117W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -<br/>504810N 0010930W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1582839167,50.8028401667,609.6 -1.1571086989,50.8047583725,609.6 -1.1558333333,50.8066666667,609.6 -1.1880555556,50.8469444444,609.6 -1.1932506097,50.8479990642,609.6 -1.1985905574,50.8487067777,609.6 -1.2040177313,50.8490599417,609.6 -1.2094735156,50.8490547418,609.6 -1.2148989838,50.8486912341,609.6 -1.220235539,50.8479733448,609.6 -1.2254255503,50.846908827,609.6 -1.2304129795,50.845509177,609.6 -1.235143989,50.8437895092,609.6 -1.2395675256,50.8417683916,609.6 -1.2436358739,50.8394676448,609.6 -1.2473051718,50.8369121049,609.6 -1.250535884,50.8341293541,609.6 -1.2532932278,50.831149422,609.6 -1.2555475458,50.82800446,609.6 -1.2572746236,50.8247283936,609.6 -1.2584559467,50.8213565552,609.6 -1.259078896,50.8179253026,609.6 -1.2591368788,50.8144716262,609.6 -1.2586293949,50.8110327501,609.6 -1.2575620362,50.8076457307,609.6 -1.2559464215,50.8043470578,609.6 -1.2538000663,50.8011722618,609.6 -1.2511461895,50.7981555319,609.6 -1.2480134597,50.7953293487,609.6 -1.244435683,50.7927241356,609.6 -1.2404514373,50.7903679324,609.6 -1.2361036556,50.788286095,609.6 -1.2314391635,50.7865010235,609.6 -1.2265081763,50.7850319225,609.6 -1.2213637601,50.7838945957,609.6 -1.2160612632,50.7831012768,609.6 -1.210657724,50.7826604986,609.6 -1.2052112607,50.7825770017,609.6 -1.1997804503,50.7828516843,609.6 -1.1944237025,50.783481592,609.6 -1.1891986355,50.7844599498,609.6 -1.1841614599,50.7857762344,609.6 -1.1793663774,50.7874162864,609.6 -1.1748650004,50.7893624625,609.6 -1.1707057986,50.7915938234,609.6 -1.1669335786,50.7940863583,609.6 -1.1635890021,50.7968132421,609.6 -1.1607081469,50.7997451229,609.6 -1.1582839167,50.8028401667,609.6 + + + + + + EGRU013B LEE-ON-SOLENT RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8037" txt_name="LEE-ON-SOLENT RWY 05"><tr><td>504641N 0011523W -<br/>504704N 0011559W -<br/>504744N 0011455W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to<br/>504721N 0011419W -<br/>504641N 0011523W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2564055556,50.7780111111,609.6 -1.2384847222,50.7892997778,609.6 -1.2421148936,50.7912314979,609.6 -1.2454559012,50.793362658,609.6 -1.2484805278,50.7956759444,609.6 -1.2663916667,50.7843916667,609.6 -1.2564055556,50.7780111111,609.6 + + + + + + EGRU013C LEE-ON-SOLENT RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7859" txt_name="LEE-ON-SOLENT RWY 23"><tr><td>505115N 0010919W -<br/>505052N 0010843W -<br/>504947N 0011027W -<br/>505017N 0011052W -<br/>505115N 0010919W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1553555556,50.8542138889,609.6 -1.1809916111,50.83812125,609.6 -1.1742489167,50.82969575,609.6 -1.1453527778,50.8478333333,609.6 -1.1553555556,50.8542138889,609.6 + + + + + + EGRU014A FLEETLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="8145" txt_name="FLEETLANDS"><tr><td>504810N 0010929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505007N 0011010W to<br/>505054N 0011304W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to<br/>505049N 0011117W -<br/>504824N 0010921W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -<br/>504810N 0010929W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1581221111,50.8027966111,609.6 -1.1529473377,50.8036983648,609.6 -1.1479446644,50.8049300154,609.6 -1.1431662976,50.8064787134,609.6 -1.1386621169,50.8083283002,609.6 -1.1344791567,50.8104594759,609.6 -1.1306611169,50.8128499992,609.6 -1.1272479066,50.8154749189,609.6 -1.1242752277,50.818306833,609.6 -1.1217742,50.8213161733,609.6 -1.1197710347,50.8244715133,609.6 -1.118286757,50.8277398956,609.6 -1.1173369832,50.831087175,609.6 -1.1169317532,50.8344783747,609.6 -1.1170754206,50.8378780514,609.6 -1.1177666027,50.8412506657,609.6 -1.1189981896,50.8445609533,609.6 -1.120757414,50.8477742946,609.6 -1.12302598,50.8508570765,609.6 -1.1257802508,50.8537770454,609.6 -1.1289914919,50.8565036455,609.6 -1.1326261697,50.859008339,609.6 -1.1366463005,50.8612649066,609.6 -1.1410098467,50.8632497227,609.6 -1.1456711573,50.8649420041,609.6 -1.1505814465,50.8663240286,609.6 -1.1556893061,50.867381322,609.6 -1.1609412463,50.8681028098,609.6 -1.1662822588,50.8684809347,609.6 -1.1716563965,50.8685117359,609.6 -1.177007363,50.8681948906,609.6 -1.1822791063,50.8675337178,609.6 -1.1874164094,50.8665351432,609.6 -1.1923654723,50.8652096263,609.6 -1.1970744782,50.8635710497,609.6 -1.201494139,50.8616365735,609.6 -1.2055782131,50.8594264543,609.6 -1.2092839904,50.8569638318,609.6 -1.2125727394,50.8542744858,609.6 -1.2154101121,50.8513865649,609.6 -1.2177777778,50.8483333333,609.6 -1.212811389,50.8488638569,609.6 -1.2077876194,50.8490916235,609.6 -1.2027524466,50.8490145484,609.6 -1.1977519533,50.8486333371,609.6 -1.1928319027,50.8479514785,609.6 -1.1880555556,50.8469444444,609.6 -1.1558333333,50.8066666667,609.6 -1.1568187649,50.8046934234,609.6 -1.1581221111,50.8027966111,609.6 + + + + + + EGRU015A CHICHESTER/GOODWOOD + <table border="1" cellpadding="1" cellspacing="0" row_id="8155" txt_name="CHICHESTER/GOODWOOD"><tr><td>A circle, 2 NM radius, centred at 505134N 0004533W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7592222222,50.8926428309,609.6 -0.7646350982,50.8924662351,609.6 -0.7699904746,50.8919383236,609.6 -0.7752314667,50.891064704,609.6 -0.7803024122,50.889854656,609.6 -0.7851494661,50.8883210315,609.6 -0.7897211749,50.8864801183,609.6 -0.7939690258,50.884351465,609.6 -0.7978479626,50.8819576735,609.6 -0.8013168646,50.8793241567,609.6 -0.8043389827,50.8764788684,609.6 -0.806882328,50.8734520048,609.6 -0.8089200087,50.8702756833,609.6 -0.8104305127,50.8669836003,609.6 -0.8113979313,50.8636106732,609.6 -0.8118121241,50.8601926694,609.6 -0.8116688211,50.8567658264,609.6 -0.8109696633,50.8533664676,609.6 -0.8097221799,50.8500306172,609.6 -0.8079397036,50.8467936188,609.6 -0.8056412244,50.8436897616,609.6 -0.8028511848,50.8407519178,609.6 -0.799599217,50.8380111956,609.6 -0.7959198265,50.8354966104,609.6 -0.791852025,50.8332347793,609.6 -0.7874389163,50.8312496404,609.6 -0.7827272404,50.8295622006,609.6 -0.7777668794,50.8281903142,609.6 -0.7726103315,50.8271484956,609.6 -0.767312158,50.8264477661,609.6 -0.7619284093,50.8260955385,609.6 -0.7565160352,50.8260955385,609.6 -0.7511322865,50.8264477661,609.6 -0.745834113,50.8271484956,609.6 -0.740677565,50.8281903142,609.6 -0.735717204,50.8295622006,609.6 -0.7310055281,50.8312496404,609.6 -0.7265924195,50.8332347793,609.6 -0.722524618,50.8354966104,609.6 -0.7188452275,50.8380111956,609.6 -0.7155932597,50.8407519178,609.6 -0.7128032201,50.8436897616,609.6 -0.7105047409,50.8467936188,609.6 -0.7087222645,50.8500306172,609.6 -0.7074747811,50.8533664676,609.6 -0.7067756234,50.8567658264,609.6 -0.7066323204,50.8601926694,609.6 -0.7070465132,50.8636106732,609.6 -0.7080139318,50.8669836003,609.6 -0.7095244357,50.8702756833,609.6 -0.7115621164,50.8734520048,609.6 -0.7141054617,50.8764788684,609.6 -0.7171275798,50.8793241567,609.6 -0.7205964818,50.8819576735,609.6 -0.7244754186,50.884351465,609.6 -0.7287232695,50.8864801183,609.6 -0.7332949784,50.8883210315,609.6 -0.7381420322,50.889854656,609.6 -0.7432129777,50.891064704,609.6 -0.7484539698,50.8919383236,609.6 -0.7538093463,50.8924662351,609.6 -0.7592222222,50.8926428309,609.6 + + + + + + EGRU015B CHICHESTER/GOODWOOD RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8188" txt_name="CHICHESTER/GOODWOOD RWY 06"><tr><td>504950N 0004906W -<br/>505017N 0004934W -<br/>505045N 0004826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505018N 0004800W -<br/>504950N 0004906W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8182694444,50.8306472222,609.6 -0.7998924444,50.8382355,609.6 -0.8027345357,50.8406427633,609.6 -0.8052225033,50.8432024379,609.6 -0.8073360278,50.8458936944,609.6 -0.8260138889,50.8381805556,609.6 -0.8182694444,50.8306472222,609.6 + + + + + + EGRU015C CHICHESTER/GOODWOOD RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7829" txt_name="CHICHESTER/GOODWOOD RWY 24"><tr><td>505327N 0004155W -<br/>505300N 0004127W -<br/>505228N 0004244W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505254N 0004313W -<br/>505327N 0004155W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6984805556,50.8907361111,609.6 -0.7203087222,50.8817591667,609.6 -0.7172734829,50.8794467216,609.6 -0.7145805628,50.8769704557,609.6 -0.7122518611,50.8743505833,609.6 -0.690725,50.8832027778,609.6 -0.6984805556,50.8907361111,609.6 + + + + + + EGRU015D CHICHESTER/GOODWOOD RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="8106" txt_name="CHICHESTER/GOODWOOD RWY 10"><tr><td>505207N 0005003W -<br/>505239N 0004952W -<br/>505226N 0004824W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505155N 0004840W -<br/>505207N 0005003W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8341805556,50.8686861111,609.6 -0.8109841389,50.8653005833,609.6 -0.8099217522,50.8682414599,609.6 -0.8084429209,50.871109396,609.6 -0.8065597222,50.8738808333,609.6 -0.830975,50.8774444444,609.6 -0.8341805556,50.8686861111,609.6 + + + + + + EGRU015E CHICHESTER/GOODWOOD RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7825" txt_name="CHICHESTER/GOODWOOD RWY 28"><tr><td>505121N 0004059W -<br/>505049N 0004110W -<br/>505101N 0004231W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505133N 0004224W -<br/>505121N 0004059W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6829166667,50.8557472222,609.6 -0.7066161944,50.85923425,609.6 -0.7068499452,50.8562211947,609.6 -0.7075135292,50.8532338934,609.6 -0.7086014167,50.8502968611,609.6 -0.6861194444,50.8469888889,609.6 -0.6829166667,50.8557472222,609.6 + + + + + + EGRU015F CHICHESTER/GOODWOOD RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="7662" txt_name="CHICHESTER/GOODWOOD RWY 14"><tr><td>505338N 0004857W -<br/>505359N 0004818W -<br/>505314N 0004717W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505253N 0004755W -<br/>505338N 0004857W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8157194444,50.8937666667,609.6 -0.7987409722,50.8813309167,609.6 -0.7954479731,50.883496282,609.6 -0.7918594971,50.8854649223,609.6 -0.7880047778,50.8872207778,609.6 -0.8049527778,50.8996361111,609.6 -0.8157194444,50.8937666667,609.6 + + + + + + EGRU015G CHICHESTER/GOODWOOD RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="7683" txt_name="CHICHESTER/GOODWOOD RWY 32"><tr><td>504930N 0004212W -<br/>504909N 0004250W -<br/>504953N 0004350W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to<br/>505014N 0004312W -<br/>504930N 0004212W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7032166667,50.8249722222,609.6 -0.7198981944,50.8372372778,609.6 -0.7232070255,50.8350833674,609.6 -0.726808746,50.8331270285,609.6 -0.7306740278,50.8313841667,609.6 -0.7139638889,50.8191,609.6 -0.7032166667,50.8249722222,609.6 + + + + + + EGRU016A SHOREHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7752" txt_name="SHOREHAM"><tr><td>A circle, 2 NM radius, centred at 505008N 0001750W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2972222222,50.8688513007,609.6 -0.3026323425,50.8686747043,609.6 -0.3079849926,50.8681467909,609.6 -0.3132233168,50.8672731683,609.6 -0.3182916812,50.866063116,609.6 -0.3231362684,50.8645294861,609.6 -0.3277056511,50.8626885662,609.6 -0.3319513412,50.8605599052,609.6 -0.3358283055,50.8581661049,609.6 -0.3392954441,50.8555325783,609.6 -0.3423160267,50.8526872793,609.6 -0.3448580805,50.8496604042,609.6 -0.3468947274,50.8464840704,609.6 -0.348404466,50.8431919744,609.6 -0.3493713957,50.8398190339,609.6 -0.3497853811,50.8364010162,609.6 -0.3496421542,50.8329741592,609.6 -0.3489433551,50.8295747861,609.6 -0.347696509,50.8262389215,609.6 -0.3459149416,50.8230019092,609.6 -0.3436176333,50.8198980385,609.6 -0.340829014,50.8169601818,609.6 -0.3375787007,50.8142194473,609.6 -0.3339011814,50.8117048508,609.6 -0.329835448,50.8094430095,609.6 -0.3254245824,50.8074578615,609.6 -0.3207153007,50.8057704138,609.6 -0.3157574598,50.804398521,609.6 -0.3106035313,50.8033566975,609.6 -0.305308049,50.8026559648,609.6 -0.2999270348,50.8023037355,609.6 -0.2945174097,50.8023037355,609.6 -0.2891363954,50.8026559648,609.6 -0.2838409131,50.8033566975,609.6 -0.2786869846,50.804398521,609.6 -0.2737291437,50.8057704138,609.6 -0.2690198621,50.8074578615,609.6 -0.2646089964,50.8094430095,609.6 -0.260543263,50.8117048508,609.6 -0.2568657438,50.8142194473,609.6 -0.2536154305,50.8169601818,609.6 -0.2508268112,50.8198980385,609.6 -0.2485295029,50.8230019092,609.6 -0.2467479354,50.8262389215,609.6 -0.2455010893,50.8295747861,609.6 -0.2448022902,50.8329741592,609.6 -0.2446590634,50.8364010162,609.6 -0.2450730487,50.8398190339,609.6 -0.2460399785,50.8431919744,609.6 -0.2475497171,50.8464840704,609.6 -0.249586364,50.8496604042,609.6 -0.2521284177,50.8526872793,609.6 -0.2551490003,50.8555325783,609.6 -0.258616139,50.8581661049,609.6 -0.2624931032,50.8605599052,609.6 -0.2667387934,50.8626885662,609.6 -0.2713081761,50.8645294861,609.6 -0.2761527632,50.866063116,609.6 -0.2812211277,50.8672731683,609.6 -0.2864594519,50.8681467909,609.6 -0.291812102,50.8686747043,609.6 -0.2972222222,50.8688513007,609.6 + + + + + + EGRU016B SHOREHAM RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="7539" txt_name="SHOREHAM RWY 02"><tr><td>504721N 0001907W -<br/>504733N 0001954W -<br/>504824N 0001923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>504812N 0001836W -<br/>504721N 0001907W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3185777778,50.7893027778,609.6 -0.3098738056,50.8032385556,609.6 -0.3144202236,50.8040923247,609.6 -0.3188268489,50.8052022003,609.6 -0.3230578611,50.8065591389,609.6 -0.3317638889,50.7926138889,609.6 -0.3185777778,50.7893027778,609.6 + + + + + + EGRU016C SHOREHAM RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7882" txt_name="SHOREHAM RWY 20"><tr><td>505257N 0001632W -<br/>505245N 0001544W -<br/>505153N 0001617W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>505204N 0001705W -<br/>505257N 0001632W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2755388889,50.8825166667,609.6 -0.2846998611,50.8678939167,609.6 -0.2801439923,50.8670472756,609.6 -0.2757274932,50.865943994,609.6 -0.2714863889,50.8645930833,609.6 -0.2623277778,50.8792055556,609.6 -0.2755388889,50.8825166667,609.6 + + + + + + EGRU016D SHOREHAM RWY 02G + <table border="1" cellpadding="1" cellspacing="0" row_id="7556" txt_name="SHOREHAM RWY 02G"><tr><td>504726N 0001901W -<br/>504737N 0001949W -<br/>504823N 0001920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>504811N 0001833W -<br/>504726N 0001901W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3169555556,50.7904222222,609.6 -0.3090648333,50.80311575,609.6 -0.3136313441,50.8039237264,609.6 -0.3180645222,50.8049890836,609.6 -0.3223283333,50.8063031667,609.6 -0.3301472222,50.7937194444,609.6 -0.3169555556,50.7904222222,609.6 + + + + + + EGRU016E SHOREHAM RWY 20G + <table border="1" cellpadding="1" cellspacing="0" row_id="8178" txt_name="SHOREHAM RWY 20G"><tr><td>505257N 0001630W -<br/>505245N 0001542W -<br/>505152N 0001615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>505204N 0001703W -<br/>505257N 0001630W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2749555556,50.8823888889,609.6 -0.2840571944,50.8677914722,609.6 -0.2795191306,50.8669086685,609.6 -0.2751254908,50.8657704377,609.6 -0.2709121111,50.8643860556,609.6 -0.2617388889,50.8790916667,609.6 -0.2749555556,50.8823888889,609.6 + + + + + + EGRU016F SHOREHAM RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8039" txt_name="SHOREHAM RWY 06"><tr><td>504834N 0002129W -<br/>504903N 0002152W -<br/>504924N 0002046W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>504856N 0002021W -<br/>504834N 0002129W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3579972222,50.8094305556,609.6 -0.3390849167,50.8154169167,609.6 -0.3417847915,50.8178920876,609.6 -0.3441212182,50.8205114974,609.6 -0.3460750833,50.8232537778,609.6 -0.3643305556,50.817475,609.6 -0.3579972222,50.8094305556,609.6 + + + + + + EGRU016G SHOREHAM RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7626" txt_name="SHOREHAM RWY 24"><tr><td>505136N 0001347W -<br/>505107N 0001324W -<br/>505041N 0001448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>505110N 0001508W -<br/>505136N 0001347W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2297,50.8599916667,609.6 -0.2523026944,50.8528699444,609.6 -0.2500184701,50.8502315888,609.6 -0.2481200116,50.8474734479,609.6 -0.2466227778,50.8446180556,609.6 -0.2233611111,50.8519472222,609.6 -0.2297,50.8599916667,609.6 + + + + + + EGRU016H SHOREHAM RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="7984" txt_name="SHOREHAM RWY 13"><tr><td>505137N 0002125W -<br/>505204N 0002056W -<br/>505137N 0001956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>505113N 0002029W -<br/>505137N 0002125W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3568833333,50.8602972222,609.6 -0.3414891667,50.8535313333,609.6 -0.3387353645,50.8559970128,609.6 -0.3356396771,50.8582945513,609.6 -0.3322275556,50.8604050278,609.6 -0.3487722222,50.8676777778,609.6 -0.3568833333,50.8602972222,609.6 + + + + + + EGRU016I SHOREHAM RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="8081" txt_name="SHOREHAM RWY 31"><tr><td>504851N 0001339W -<br/>504825N 0001408W -<br/>504856N 0001519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to<br/>504924N 0001454W -<br/>504851N 0001339W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2274555556,50.8142416667,609.6 -0.2482630278,50.8234243611,609.6 -0.250200315,50.8206661153,609.6 -0.2525237726,50.8180303055,609.6 -0.2552142778,50.8155385833,609.6 -0.2355555556,50.8068638889,609.6 -0.2274555556,50.8142416667,609.6 + + + + + + EGRU017A LYDD + <table border="1" cellpadding="1" cellspacing="0" row_id="7932" txt_name="LYDD"><tr><td>A circle, 2 NM radius, centred at 505722N 0005621E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.93915,50.9894700535,609.6 0.93372587,50.9892934602,609.6 0.9283593595,50.9887655562,609.6 0.923107472,50.9878919491,609.6 0.9180259857,50.9866819185,609.6 0.9131688582,50.9851483162,609.6 0.9085876498,50.9833074298,609.6 0.9043309744,50.981178808,609.6 0.900443982,50.9787850521,609.6 0.8969678786,50.9761515751,609.6 0.8939394896,50.9733063304,609.6 0.8913908701,50.9702795138,609.6 0.8893489674,50.9671032423,609.6 0.8878353379,50.9638112119,609.6 0.8868659227,50.9604383396,609.6 0.886450883,50.9570203922,609.6 0.8865944969,50.9535936066,609.6 0.8872951194,50.9501943055,609.6 0.8885452053,50.9468585126,609.6 0.8903313938,50.9436215708,609.6 0.8926346547,50.9405177686,609.6 0.8954304945,50.9375799776,609.6 0.8986892193,50.9348393051,609.6 0.9023762517,50.932324766,609.6 0.9064524989,50.9300629769,609.6 0.9108747678,50.9280778751,609.6 0.9155962214,50.926390467,609.6 0.9205668744,50.9250186065,609.6 0.92573412,50.9239768078,609.6 0.9310432838,50.9232760917,609.6 0.9364381998,50.9229238708,609.6 0.9418618002,50.9229238708,609.6 0.9472567162,50.9232760917,609.6 0.95256588,50.9239768078,609.6 0.9577331256,50.9250186065,609.6 0.9627037786,50.926390467,609.6 0.9674252322,50.9280778751,609.6 0.9718475011,50.9300629769,609.6 0.9759237483,50.932324766,609.6 0.9796107807,50.9348393051,609.6 0.9828695055,50.9375799776,609.6 0.9856653453,50.9405177686,609.6 0.9879686062,50.9436215708,609.6 0.9897547947,50.9468585126,609.6 0.9910048806,50.9501943055,609.6 0.9917055031,50.9535936066,609.6 0.991849117,50.9570203922,609.6 0.9914340773,50.9604383396,609.6 0.9904646621,50.9638112119,609.6 0.9889510326,50.9671032423,609.6 0.9869091299,50.9702795138,609.6 0.9843605104,50.9733063304,609.6 0.9813321214,50.9761515751,609.6 0.977856018,50.9787850521,609.6 0.9739690256,50.981178808,609.6 0.9697123502,50.9833074298,609.6 0.9651311418,50.9851483162,609.6 0.9602740143,50.9866819185,609.6 0.955192528,50.9878919491,609.6 0.9499406405,50.9887655562,609.6 0.94457413,50.9892934602,609.6 0.93915,50.9894700535,609.6 + + + + + + EGRU017B LYDD RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7566" txt_name="LYDD RWY 03"><tr><td>505437N 0005403E -<br/>505454N 0005320E -<br/>505551N 0005418E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to<br/>505534N 0005501E -<br/>505437N 0005403E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9009277778,50.9102333333,609.6 0.9169214722,50.9259866667,609.6 0.9127054288,50.927375169,609.6 0.9087043516,50.9289980997,609.6 0.9049507778,50.93084225,609.6 0.8889638889,50.9150916667,609.6 0.9009277778,50.9102333333,609.6 + + + + + + EGRU017C LYDD RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7571" txt_name="LYDD RWY 21"><tr><td>510007N 0005838E -<br/>505949N 0005921E -<br/>505853N 0005824E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to<br/>505911N 0005741E -<br/>510007N 0005838E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9771694444,51.0018333333,609.6 0.9614053611,50.9863595278,609.6 0.9656253748,50.9849693767,609.6 0.9696293844,50.9833446153,609.6 0.97338475,50.9814985,609.6 0.9891555556,50.996975,609.6 0.9771694444,51.0018333333,609.6 + + + + + + EGRU019A LERWICK/TINGWALL + <table border="1" cellpadding="1" cellspacing="0" row_id="7523" txt_name="LERWICK/TINGWALL"><tr><td>A circle, 2 NM radius, centred at 601131N 0011437W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2436111111,60.2251892731,609.6 -1.25048308,60.2250128939,609.6 -1.2572819849,60.2244856317,609.6 -1.2639355456,60.2236130921,609.6 -1.2703730408,60.2224045513,609.6 -1.2765260659,60.2208728561,609.6 -1.2823292652,60.2190342866,609.6 -1.2877210302,60.2169083816,609.6 -1.2926441565,60.2145177293,609.6 -1.2970464527,60.2118877258,609.6 -1.3008812932,60.2090463035,609.6 -1.3041081112,60.2060236326,609.6 -1.3066928252,60.2028517994,609.6 -1.3086081946,60.1995644641,609.6 -1.3098341021,60.1961965024,609.6 -1.3103577589,60.1927836347,609.6 -1.3101738317,60.1893620465,609.6 -1.3092844896,60.1859680046,609.6 -1.3076993726,60.1826374726,609.6 -1.3054354794,60.1794057306,609.6 -1.30251698,60.176307002,609.6 -1.2989749513,60.1733740921,609.6 -1.2948470426,60.1706380425,609.6 -1.2901770716,60.1681278037,609.6 -1.2850145576,60.1658699305,609.6 -1.2794141959,60.1638883032,609.6 -1.2734352793,60.162203876,609.6 -1.2671410726,60.1608344578,609.6 -1.2605981468,60.1597945248,609.6 -1.2538756796,60.1590950691,609.6 -1.2470447298,60.1587434834,609.6 -1.2401774924,60.1587434834,609.6 -1.2333465426,60.1590950691,609.6 -1.2266240754,60.1597945248,609.6 -1.2200811496,60.1608344578,609.6 -1.2137869429,60.162203876,609.6 -1.2078080264,60.1638883032,609.6 -1.2022076647,60.1658699305,609.6 -1.1970451506,60.1681278037,609.6 -1.1923751796,60.1706380425,609.6 -1.1882472709,60.1733740921,609.6 -1.1847052422,60.176307002,609.6 -1.1817867428,60.1794057306,609.6 -1.1795228496,60.1826374726,609.6 -1.1779377326,60.1859680046,609.6 -1.1770483906,60.1893620465,609.6 -1.1768644633,60.1927836347,609.6 -1.1773881202,60.1961965024,609.6 -1.1786140277,60.1995644641,609.6 -1.180529397,60.2028517994,609.6 -1.183114111,60.2060236326,609.6 -1.1863409291,60.2090463035,609.6 -1.1901757695,60.2118877258,609.6 -1.1945780657,60.2145177293,609.6 -1.1995011921,60.2169083816,609.6 -1.204892957,60.2190342866,609.6 -1.2106961563,60.2208728561,609.6 -1.2168491815,60.2224045513,609.6 -1.2232866766,60.2236130921,609.6 -1.2299402373,60.2244856317,609.6 -1.2367391422,60.2250128939,609.6 -1.2436111111,60.2251892731,609.6 + + + + + + EGRU019B LERWICK/TINGWALL RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8067" txt_name="LERWICK/TINGWALL RWY 02"><tr><td>600839N 0011524W -<br/>600847N 0011627W -<br/>600939N 0011603W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to<br/>600932N 0011500W -<br/>600839N 0011524W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2567777778,60.1442333333,609.6 -1.2499103611,60.1588478889,609.6 -1.2558708651,60.1592652753,609.6 -1.2617318323,60.1599485109,609.6 -1.2674456667,60.1608920556,609.6 -1.2743027778,60.1462833333,609.6 -1.2567777778,60.1442333333,609.6 + + + + + + EGRU019C LERWICK/TINGWALL RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="8104" txt_name="LERWICK/TINGWALL RWY 20"><tr><td>601424N 0011349W -<br/>601417N 0011245W -<br/>601323N 0011311W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to<br/>601330N 0011414W -<br/>601424N 0011349W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2301611111,60.2400916667,609.6 -1.2372617778,60.22503875,609.6 -1.2312903432,60.2246189182,609.6 -1.2254195327,60.2239327561,609.6 -1.2196972778,60.2229858889,609.6 -1.2125861111,60.2380444444,609.6 -1.2301611111,60.2400916667,609.6 + + + + + + EGRU020 HMP CHANNINGS WOOD + <table border="1" cellpadding="1" cellspacing="0" row_id="14064" txt_name="HMP CHANNINGS WOOD"><tr><td>503110N 0033918W -<br/>503108N 0033842W -<br/>503054N 0033836W -<br/>503029N 0033847W -<br/>503022N 0033920W -<br/>503034N 0033946W -<br/>503049N 0033947W -<br/>503110N 0033918W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 291 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.655,50.5194,213.36 -3.6629972222,50.513475,213.36 -3.6626555556,50.5095444444,213.36 -3.6555166667,50.5061305556,213.36 -3.6463638889,50.5079861111,213.36 -3.6433027778,50.5149527778,213.36 -3.6451,50.5187722222,213.36 -3.655,50.5194,213.36 + + + + + + EGRU021 HMP DARTMOOR + <table border="1" cellpadding="1" cellspacing="0" row_id="14114" txt_name="HMP DARTMOOR"><tr><td>503318N 0035946W -<br/>503312N 0035925W -<br/>503259N 0035917W -<br/>503247N 0035924W -<br/>503235N 0035957W -<br/>503308N 0040020W -<br/>503318N 0035946W <br/>Upper limit: 1900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 1403 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9961305556,50.5549111111,579.12 -4.0056361111,50.5521527778,579.12 -3.9991277778,50.5430111111,579.12 -3.9899416667,50.5463833333,579.12 -3.9880027778,50.5496972222,579.12 -3.9904138889,50.5534277778,579.12 -3.9961305556,50.5549111111,579.12 + + + + + + EGRU022 HMP EXETER + <table border="1" cellpadding="1" cellspacing="0" row_id="14153" txt_name="HMP EXETER"><tr><td>504400N 0033157W -<br/>504357N 0033136W -<br/>504332N 0033124W -<br/>504325N 0033218W -<br/>504352N 0033230W -<br/>504400N 0033157W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 184 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.5325777778,50.7332972222,182.88 -3.5415472222,50.731125,182.88 -3.5382944444,50.7234888889,182.88 -3.5232972222,50.7256,182.88 -3.526575,50.7326305556,182.88 -3.5325777778,50.7332972222,182.88 + + + + + + EGRU023 HMP GUYS MARSH + <table border="1" cellpadding="1" cellspacing="0" row_id="14144" txt_name="HMP GUYS MARSH"><tr><td>505925N 0021325W -<br/>505928N 0021252W -<br/>505901N 0021229W -<br/>505842N 0021316W -<br/>505909N 0021348W -<br/>505925N 0021325W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 346 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2236361111,50.9901722222,243.84 -2.2300527778,50.9858083333,243.84 -2.2209777778,50.9782111111,243.84 -2.2080888889,50.9837472222,243.84 -2.2145111111,50.9911916667,243.84 -2.2236361111,50.9901722222,243.84 + + + + + + EGRU024 HMP ISLE OF WIGHT + <table border="1" cellpadding="1" cellspacing="0" row_id="14151" txt_name="HMP ISLE OF WIGHT"><tr><td>504308N 0011912W -<br/>504318N 0011810W -<br/>504227N 0011750W -<br/>504216N 0011840W -<br/>504308N 0011912W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 157 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3200083333,50.7187833333,182.88 -1.3110416667,50.7045388889,182.88 -1.2973027778,50.7075833333,182.88 -1.3026555556,50.7215638889,182.88 -1.3200083333,50.7187833333,182.88 + + + + + + EGRU025 HMP LEWES + <table border="1" cellpadding="1" cellspacing="0" row_id="14095" txt_name="HMP LEWES"><tr><td>505243N 0000018W -<br/>505231N 0000006E -<br/>505216N 0000007E -<br/>505200N 0000032W -<br/>505228N 0000058W -<br/>505243N 0000018W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 207 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0049527778,50.8787138889,213.36 -0.01605,50.874425,213.36 -0.0089611111,50.8666,213.36 0.00205,50.8709777778,213.36 0.0016305556,50.8752805556,213.36 -0.0049527778,50.8787138889,213.36 + + + + + + EGRU026 HMP PORTLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="14065" txt_name="HMP PORTLAND"><tr><td>503323N 0022549W -<br/>503325N 0022513W -<br/>503306N 0022455W -<br/>503247N 0022444W -<br/>503243N 0022529W -<br/>503306N 0022556W -<br/>503323N 0022549W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 382 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.430325,50.5564944444,243.84 -2.43215,50.5517,243.84 -2.4248138889,50.5452805556,243.84 -2.4123027778,50.5464833333,243.84 -2.4152,50.5516916667,243.84 -2.4202333333,50.55705,243.84 -2.430325,50.5564944444,243.84 + + + + + + EGRU027 HMP THE VERNE + <table border="1" cellpadding="1" cellspacing="0" row_id="14067" txt_name="HMP THE VERNE"><tr><td>503359N 0022615W -<br/>503358N 0022546W -<br/>503333N 0022528W -<br/>503320N 0022612W -<br/>503326N 0022617W -<br/>503327N 0022640W -<br/>503351N 0022636W -<br/>503359N 0022615W <br/>Upper limit: 900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 476 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4375472222,50.5662944444,274.32 -2.4433861111,50.5640555556,274.32 -2.4445305556,50.5574805556,274.32 -2.4380888889,50.5572861111,274.32 -2.4366027778,50.5555277778,274.32 -2.4245555556,50.5591222222,274.32 -2.4293055556,50.5659888889,274.32 -2.4375472222,50.5662944444,274.32 + + + + + + EGRU101A HAVERFORDWEST + <table border="1" cellpadding="1" cellspacing="0" row_id="7534" txt_name="HAVERFORDWEST"><tr><td>A circle, 2 NM radius, centred at 515000N 0045739W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9608472222,51.866601154,609.6 -4.9663762085,51.8664245833,609.6 -4.9718464575,51.8658967469,609.6 -4.97719986,51.8650232521,609.6 -4.9823795559,51.8638133777,609.6 -4.9873305421,51.8622799751,609.6 -4.9920002595,51.8604393304,609.6 -4.9963391531,51.8583109909,609.6 -5.0003012001,51.8559175563,609.6 -5.0038443986,51.8532844373,609.6 -5.0069312133,51.8504395846,609.6 -5.0095289721,51.8474131912,609.6 -5.0116102105,51.8442373706,609.6 -5.0131529595,51.8409458148,609.6 -5.0141409747,51.8375734365,609.6 -5.0145639039,51.8341559975,609.6 -5.0144173916,51.8307297297,609.6 -5.0137031196,51.8273309503,609.6 -5.0124287842,51.8239956769,609.6 -5.010608009,51.8207592466,609.6 -5.0082601956,51.8176559415,609.6 -5.0054103137,51.8147186271,609.6 -5.0020886333,51.8119784046,609.6 -4.9983304008,51.8094642829,609.6 -4.9941754641,51.8072028728,609.6 -4.9896678499,51.8052181066,609.6 -4.9848552974,51.8035309858,609.6 -4.9797887545,51.8021593605,609.6 -4.9745218403,51.8011177411,609.6 -4.9691102802,51.8004171461,609.6 -4.9636113201,51.8000649862,609.6 -4.9580831243,51.8000649862,609.6 -4.9525841643,51.8004171461,609.6 -4.9471726042,51.8011177411,609.6 -4.9419056899,51.8021593605,609.6 -4.9368391471,51.8035309858,609.6 -4.9320265946,51.8052181066,609.6 -4.9275189803,51.8072028728,609.6 -4.9233640436,51.8094642829,609.6 -4.9196058111,51.8119784046,609.6 -4.9162841307,51.8147186271,609.6 -4.9134342489,51.8176559415,609.6 -4.9110864354,51.8207592466,609.6 -4.9092656602,51.8239956769,609.6 -4.9079913248,51.8273309503,609.6 -4.9072770529,51.8307297297,609.6 -4.9071305405,51.8341559975,609.6 -4.9075534697,51.8375734365,609.6 -4.908541485,51.8409458148,609.6 -4.9100842339,51.8442373706,609.6 -4.9121654723,51.8474131912,609.6 -4.9147632311,51.8504395846,609.6 -4.9178500458,51.8532844373,609.6 -4.9213932444,51.8559175563,609.6 -4.9253552913,51.8583109909,609.6 -4.929694185,51.8604393304,609.6 -4.9343639023,51.8622799751,609.6 -4.9393148885,51.8638133777,609.6 -4.9444945845,51.8650232521,609.6 -4.9498479869,51.8658967469,609.6 -4.9553182359,51.8664245833,609.6 -4.9608472222,51.866601154,609.6 + + + + + + EGRU101B HAVERFORDWEST RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7687" txt_name="HAVERFORDWEST RWY 03"><tr><td>514716N 0045940W -<br/>514732N 0050025W -<br/>514825N 0045937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to<br/>514809N 0045851W -<br/>514716N 0045940W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9943083333,51.7878444444,609.6 -4.9809063333,51.8024292222,609.6 -4.9853153742,51.8036751517,609.6 -4.9895255747,51.8051622529,609.6 -4.9935026944,51.8068784444,609.6 -5.0068972222,51.7922972222,609.6 -4.9943083333,51.7878444444,609.6 + + + + + + EGRU101C HAVERFORDWEST RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="8184" txt_name="HAVERFORDWEST RWY 21"><tr><td>515243N 0045539W -<br/>515227N 0045454W -<br/>515135N 0045541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to<br/>515151N 0045627W -<br/>515243N 0045539W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.9275583333,51.8785055556,609.6 -4.9407586667,51.8641889167,609.6 -4.9363448359,51.8629411724,609.6 -4.9321309303,51.8614520004,609.6 -4.9281513056,51.8597335556,609.6 -4.9149444444,51.8740527778,609.6 -4.9275583333,51.8785055556,609.6 + + + + + + EGRU101D HAVERFORDWEST RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7929" txt_name="HAVERFORDWEST RWY 09"><tr><td>514940N 0050222W -<br/>515012N 0050224W -<br/>515015N 0050051W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to<br/>514942N 0050050W -<br/>514940N 0050222W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.0394888889,51.8277361111,609.6 -5.0139970278,51.8284296389,609.6 -5.0144928085,51.8314198647,609.6 -5.0145512565,51.8344256075,609.6 -5.0141718056,51.8374223611,609.6 -5.0401138889,51.8367166667,609.6 -5.0394888889,51.8277361111,609.6 + + + + + + EGRU101E HAVERFORDWEST RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7955" txt_name="HAVERFORDWEST RWY 27"><tr><td>515027N 0045311W -<br/>514955N 0045309W -<br/>514953N 0045426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to<br/>515025N 0045430W -<br/>515027N 0045311W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.886525,51.8408111111,609.6 -4.9082875833,51.8402431944,609.6 -4.9074941979,51.8372777002,609.6 -4.9071359293,51.8342799592,609.6 -4.9072156111,51.8312744167,609.6 -4.8859027778,51.8318305556,609.6 -4.886525,51.8408111111,609.6 + + + + + + EGRU103A SWANSEA + <table border="1" cellpadding="1" cellspacing="0" row_id="7681" txt_name="SWANSEA"><tr><td>A circle, 2 NM radius, centred at 513619N 0040404W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0677777778,51.6385691199,609.6 -4.0732789905,51.6383925433,609.6 -4.0787217619,51.6378646894,609.6 -4.0840482758,51.6369911656,609.6 -4.0892019586,51.6357812508,609.6 -4.0941280843,51.6342477966,609.6 -4.0987743581,51.6324070894,609.6 -4.1030914745,51.6302786768,609.6 -4.1070336417,51.6278851591,609.6 -4.1105590688,51.6252519474,609.6 -4.1136304084,51.6224069933,609.6 -4.1162151518,51.6193804903,609.6 -4.1182859716,51.6162045529,609.6 -4.1198210079,51.6129128741,609.6 -4.1208040969,51.6095403677,609.6 -4.1212249367,51.606122797,609.6 -4.1210791924,51.6026963949,609.6 -4.120368536,51.5992974802,609.6 -4.1191006239,51.595962072,609.6 -4.1172890099,51.592725509,609.6 -4.1149529973,51.5896220749,609.6 -4.1121174298,51.5866846367,609.6 -4.1088124245,51.5839442973,609.6 -4.1050730509,51.5814300673,609.6 -4.1009389566,51.5791685587,609.6 -4.0964539477,51.5771837053,609.6 -4.0916655245,51.5754965099,609.6 -4.0866243798,51.5741248235,609.6 -4.0813838645,51.5730831575,609.6 -4.0759994259,51.572382531,609.6 -4.0705280237,51.5720303553,609.6 -4.0650275318,51.5720303553,609.6 -4.0595561297,51.572382531,609.6 -4.054171691,51.5730831575,609.6 -4.0489311758,51.5741248235,609.6 -4.0438900311,51.5754965099,609.6 -4.0391016078,51.5771837053,609.6 -4.0346165989,51.5791685587,609.6 -4.0304825047,51.5814300673,609.6 -4.026743131,51.5839442973,609.6 -4.0234381258,51.5866846367,609.6 -4.0206025582,51.5896220749,609.6 -4.0182665456,51.592725509,609.6 -4.0164549317,51.595962072,609.6 -4.0151870195,51.5992974802,609.6 -4.0144763632,51.6026963949,609.6 -4.0143306189,51.606122797,609.6 -4.0147514587,51.6095403677,609.6 -4.0157345476,51.6129128741,609.6 -4.017269584,51.6162045529,609.6 -4.0193404037,51.6193804903,609.6 -4.0219251472,51.6224069933,609.6 -4.0249964868,51.6252519474,609.6 -4.0285219138,51.6278851591,609.6 -4.0324640811,51.6302786768,609.6 -4.0367811974,51.6324070894,609.6 -4.0414274713,51.6342477966,609.6 -4.0463535969,51.6357812508,609.6 -4.0515072798,51.6369911656,609.6 -4.0568337937,51.6378646894,609.6 -4.0622765651,51.6383925433,609.6 -4.0677777778,51.6385691199,609.6 + + + + + + EGRU103B SWANSEA RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7967" txt_name="SWANSEA RWY 04"><tr><td>513341N 0040638W -<br/>513400N 0040720W -<br/>513453N 0040618W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to<br/>513434N 0040536W -<br/>513341N 0040638W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1105694444,51.5614305556,609.6 -4.0933516667,51.5760447778,609.6 -4.0974772875,51.5775992074,609.6 -4.1013615228,51.5793789018,609.6 -4.1049727778,51.5813693889,609.6 -4.1221888889,51.5667527778,609.6 -4.1105694444,51.5614305556,609.6 + + + + + + EGRU103C SWANSEA RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="8057" txt_name="SWANSEA RWY 22"><tr><td>513854N 0040133W -<br/>513835N 0040052W -<br/>513745N 0040150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to<br/>513804N 0040232W -<br/>513854N 0040133W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0259555556,51.6483027778,609.6 -4.0422406389,51.6345286389,609.6 -4.0381074205,51.632975828,609.6 -4.0342163026,51.631197314,609.6 -4.030599,51.6292076111,609.6 -4.0143111111,51.6429805556,609.6 -4.0259555556,51.6483027778,609.6 + + + + + + EGRU103D SWANSEA RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7736" txt_name="SWANSEA RWY 10"><tr><td>513606N 0040854W -<br/>513638N 0040848W -<br/>513632N 0040715W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to<br/>513559N 0040714W -<br/>513606N 0040854W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1483194444,51.6016305556,609.6 -4.1204896111,51.5997253611,609.6 -4.1210842429,51.602737017,609.6 -4.1212361072,51.605769878,609.6 -4.1209438611,51.60879875,609.6 -4.1467305556,51.6105638889,609.6 -4.1483194444,51.6016305556,609.6 + + + + + + EGRU103E SWANSEA RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="8113" txt_name="SWANSEA RWY 28"><tr><td>513600N 0035931W -<br/>513527N 0035937W -<br/>513534N 0040106W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to<br/>513605N 0040053W -<br/>513600N 0035931W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9918916667,51.5998777778,609.6 -4.0146683056,51.6014628333,609.6 -4.015448363,51.5984676719,609.6 -4.0166629251,51.5955291688,609.6 -4.0183018333,51.5926717222,609.6 -3.9934777778,51.5909444444,609.6 -3.9918916667,51.5998777778,609.6 + + + + + + EGRU104A ST ATHAN + <table border="1" cellpadding="1" cellspacing="0" row_id="7903" txt_name="ST ATHAN"><tr><td>512532N 0032328W -<br/>512241N 0032410W thence clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to -<br/>512532N 0032328W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3911111111,51.4255555556,609.6 -3.3947277475,51.4281636406,609.6 -3.3987267963,51.4305415517,609.6 -3.4030987649,51.4326475738,609.6 -3.4077965855,51.4344590111,609.6 -3.4127696603,51.4359563401,609.6 -3.4179644073,51.4371234209,609.6 -3.4233248408,51.4379476723,609.6 -3.4287931779,51.4384202082,609.6 -3.4343104649,51.4385359342,609.6 -3.4398172168,51.4382936026,609.6 -3.445254063,51.437695826,609.6 -3.4505623917,51.4367490491,609.6 -3.4556849849,51.4354634786,609.6 -3.4605666395,51.4338529727,609.6 -3.465154765,51.4319348906,609.6 -3.4693999519,51.4297299043,609.6 -3.4732565058,51.4272617751,609.6 -3.4766829403,51.4245570954,609.6 -3.4796424223,51.4216450019,609.6 -3.4821031677,51.4185568596,609.6 -3.4840387809,51.4153259234,609.6 -3.4854285349,51.4119869789,609.6 -3.4862575909,51.4085759665,609.6 -3.4865171524,51.4051295947,609.6 -3.4862045549,51.4016849442,609.6 -3.4853232893,51.3982790688,609.6 -3.4838829581,51.3949485973,609.6 -3.4818991679,51.3917293395,609.6 -3.4793933557,51.3886559024,609.6 -3.4763925551,51.3857613184,609.6 -3.4729291017,51.3830766918,609.6 -3.4690402832,51.3806308656,609.6 -3.4647679371,51.3784501128,609.6 -3.4601580005,51.3765578554,609.6 -3.4552600171,51.3749744143,609.6 -3.4501266063,51.3737167921,609.6 -3.4448129005,51.3727984916,609.6 -3.4393759557,51.3722293717,609.6 -3.4338741428,51.3720155421,609.6 -3.4283665243,51.3721592983,609.6 -3.4229122247,51.3726590972,609.6 -3.4175698,51.3735095732,609.6 -3.4123966127,51.3747015956,609.6 -3.4074482194,51.3762223661,609.6 -3.4027777778,51.3780555556,609.6 -3.3911111111,51.4255555556,609.6 + + + + + + EGRU104B ST ATHAN RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7920" txt_name="ST ATHAN RWY 07"><tr><td>512308N 0033043W -<br/>512339N 0033058W -<br/>512400N 0032909W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to<br/>512329N 0032854W -<br/>512308N 0033043W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.5119361111,51.3855,609.6 -3.4816345,51.3912958056,609.6 -3.483453917,51.3940757942,609.6 -3.4848655896,51.3969470432,609.6 -3.4858579444,51.3998861944,609.6 -3.5161222222,51.3940972222,609.6 -3.5119361111,51.3855,609.6 + + + + + + EGRU104C ST ATHAN RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8038" txt_name="ST ATHAN RWY 25"><tr><td>512530N 0032116W -<br/>512459N 0032101W -<br/>512428N 0032344W -<br/>512503N 0032335W -<br/>512530N 0032116W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3543944444,51.424925,609.6 -3.3930726111,51.4175764444,609.6 -3.3954943889,51.4077211111,609.6 -3.3502,51.4163277778,609.6 -3.3543944444,51.424925,609.6 + + + + + + EGRU105A CARDIFF + <table border="1" cellpadding="1" cellspacing="0" row_id="7602" txt_name="CARDIFF"><tr><td>512532N 0032328W thence clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to<br/>512241N 0032410W -<br/>512532N 0032328W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3911111111,51.4255555556,609.6 -3.4027777778,51.3780555556,609.6 -3.3998652394,51.3747004374,609.6 -3.3964158735,51.3715489884,609.6 -3.3925197597,51.3686086909,609.6 -3.3882097622,51.3659042849,609.6 -3.3835222082,51.3634585212,609.6 -3.3784965819,51.3612919717,609.6 -3.3731751922,51.3594228567,609.6 -3.367602818,51.3578668934,609.6 -3.3618263334,51.356637164,609.6 -3.3558943152,51.3557440071,609.6 -3.3498566379,51.355194931,609.6 -3.3437640568,51.3549945514,609.6 -3.337667785,51.3551445526,609.6 -3.3316190667,51.3556436737,609.6 -3.3256687493,51.3564877191,609.6 -3.3198668596,51.3576695933,609.6 -3.3142621866,51.3591793603,609.6 -3.3089018737,51.3610043263,609.6 -3.303831025,51.3631291457,609.6 -3.2990923271,51.3655359494,609.6 -3.2947256915,51.3682044938,609.6 -3.2907679193,51.3711123302,609.6 -3.2872523906,51.3742349926,609.6 -3.284208783,51.377546202,609.6 -3.2816628197,51.3810180874,609.6 -3.2796360502,51.3846214184,609.6 -3.2781456658,51.3883258514,609.6 -3.277204351,51.392100184,609.6 -3.2768201726,51.3959126172,609.6 -3.2769965071,51.3997310233,609.6 -3.2777320074,51.4035232161,609.6 -3.27902061,51.4072572226,609.6 -3.2808515811,51.4109015527,609.6 -3.283209603,51.4144254654,609.6 -3.2860748989,51.4177992282,609.6 -3.2894233972,51.4209943694,609.6 -3.2932269306,51.4239839189,609.6 -3.2974534725,51.4267426368,609.6 -3.3020674054,51.4292472279,609.6 -3.3070298211,51.4314765391,609.6 -3.3122988491,51.4334117396,609.6 -3.3178300112,51.4350364804,609.6 -3.3235765985,51.4363370339,609.6 -3.3294900682,51.4373024107,609.6 -3.3355204563,51.4379244528,609.6 -3.341616803,51.4381979032,609.6 -3.3477275864,51.4381204511,609.6 -3.3538011618,51.437692751,609.6 -3.3597862013,51.4369184174,609.6 -3.3656321314,51.435803994,609.6 -3.3712895632,51.4343588982,609.6 -3.3767107132,51.4325953402,609.6 -3.3818498086,51.4305282199,609.6 -3.3866634765,51.4281749996,609.6 -3.3911111111,51.4255555556,609.6 + + + + + + EGRU105B CARDIFF RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="8061" txt_name="CARDIFF RWY 12"><tr><td>512500N 0032523W -<br/>512529N 0032500W -<br/>512502N 0032335W -<br/>512429N 0032344W -<br/>512500N 0032523W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4230194444,51.4166861111,609.6 -3.395426,51.4079994167,609.6 -3.3931304444,51.4173411111,609.6 -3.4165416667,51.4247111111,609.6 -3.4230194444,51.4166861111,609.6 + + + + + + EGRU105C CARDIFF RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="8114" txt_name="CARDIFF RWY 30"><tr><td>512234N 0031546W -<br/>512205N 0031610W -<br/>512226N 0031715W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to<br/>512255N 0031652W -<br/>512234N 0031546W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2628444444,51.3761972222,609.6 -3.2810616111,51.3819633056,609.6 -3.2829113154,51.3791942869,609.6 -3.2850748667,51.3765158529,609.6 -3.2875409722,51.3739419167,609.6 -3.2693111111,51.3681722222,609.6 -3.2628444444,51.3761972222,609.6 + + + + + + EGRU106A BRISTOL + <table border="1" cellpadding="1" cellspacing="0" row_id="7535" txt_name="BRISTOL"><tr><td>A circle, 2.5 NM radius, centred at 512258N 0024309W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7191,51.4242851807,609.6 -2.725241868,51.4241074951,609.6 -2.731331194,51.4235759583,609.6 -2.7373158889,51.4226951174,609.6 -2.7431447661,51.421472507,609.6 -2.7487679819,51.4199185848,609.6 -2.7541374654,51.4180466408,609.6 -2.7592073311,51.4158726835,609.6 -2.7639342736,51.4134153014,609.6 -2.7682779384,51.4106955036,609.6 -2.772201267,51.4077365385,609.6 -2.7756708136,51.4045636943,609.6 -2.7786570288,51.4012040819,609.6 -2.7811345104,51.3976864016,609.6 -2.7830822176,51.3940406978,609.6 -2.7844836469,51.3902981006,609.6 -2.7853269691,51.3864905603,609.6 -2.7856051262,51.3826505733,609.6 -2.7853158864,51.3788109052,609.6 -2.7844618587,51.3750043104,609.6 -2.7830504661,51.3712632532,609.6 -2.7810938767,51.3676196314,609.6 -2.7786088966,51.3641045045,609.6 -2.7756168221,51.3607478295,609.6 -2.7721432548,51.357578207,609.6 -2.7682178809,51.3546226381,609.6 -2.7638742162,51.3519062952,609.6 -2.7591493189,51.3494523093,609.6 -2.7540834738,51.3472815737,609.6 -2.7487198497,51.3454125672,609.6 -2.7431041323,51.3438611982,609.6 -2.7372841373,51.3426406699,609.6 -2.7313094058,51.341761369,609.6 -2.7252307852,51.3412307778,609.6 -2.7191,51.341053411,609.6 -2.7129692148,51.3412307778,609.6 -2.7068905942,51.341761369,609.6 -2.7009158627,51.3426406699,609.6 -2.6950958677,51.3438611982,609.6 -2.6894801503,51.3454125672,609.6 -2.6841165262,51.3472815737,609.6 -2.6790506811,51.3494523093,609.6 -2.6743257838,51.3519062952,609.6 -2.6699821191,51.3546226381,609.6 -2.6660567452,51.357578207,609.6 -2.6625831779,51.3607478295,609.6 -2.6595911034,51.3641045045,609.6 -2.6571061233,51.3676196314,609.6 -2.6551495339,51.3712632532,609.6 -2.6537381413,51.3750043104,609.6 -2.6528841136,51.3788109052,609.6 -2.6525948738,51.3826505733,609.6 -2.6528730309,51.3864905603,609.6 -2.6537163531,51.3902981006,609.6 -2.6551177824,51.3940406978,609.6 -2.6570654896,51.3976864016,609.6 -2.6595429712,51.4012040819,609.6 -2.6625291864,51.4045636943,609.6 -2.665998733,51.4077365385,609.6 -2.6699220616,51.4106955036,609.6 -2.6742657264,51.4134153014,609.6 -2.6789926689,51.4158726835,609.6 -2.6840625346,51.4180466408,609.6 -2.6894320181,51.4199185848,609.6 -2.6950552339,51.421472507,609.6 -2.7008841111,51.4226951174,609.6 -2.706868806,51.4235759583,609.6 -2.712958132,51.4241074951,609.6 -2.7191,51.4242851807,609.6 + + + + + + EGRU106B BRISTOL RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8165" txt_name="BRISTOL RWY 09"><tr><td>512229N 0024817W -<br/>512302N 0024820W -<br/>512304N 0024708W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to<br/>512232N 0024705W -<br/>512229N 0024817W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8047333333,51.3748027778,609.6 -2.784633,51.3755981944,609.6 -2.7852789747,51.3785715963,609.6 -2.785580968,51.3815663965,609.6 -2.7855373333,51.3845670278,609.6 -2.8056222222,51.3837722222,609.6 -2.8047333333,51.3748027778,609.6 + + + + + + EGRU106C BRISTOL RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7508" txt_name="BRISTOL RWY 27"><tr><td>512325N 0023807W -<br/>512253N 0023804W -<br/>512251N 0023910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to<br/>512323N 0023913W -<br/>512325N 0023807W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6352888889,51.3904027778,609.6 -2.6535468333,51.389704,609.6 -2.6529092331,51.3867298164,609.6 -2.6526158735,51.3837346154,609.6 -2.6526682222,51.3807339722,609.6 -2.6343944444,51.3814333333,609.6 -2.6352888889,51.3904027778,609.6 + + + + + + EGRU107A YEOVILTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7803" txt_name="YEOVILTON"><tr><td>505817N 0024035W thence clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to<br/>505804N 0023747W -<br/>505817N 0024035W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6762913333,50.9714693611,609.6 -2.6298215278,50.967843,609.6 -2.6239672815,50.9689304403,609.6 -2.618297061,50.9703547957,609.6 -2.6128593738,50.9721039029,609.6 -2.6077007473,50.974162805,609.6 -2.6028653391,50.9765138932,609.6 -2.5983945605,50.9791370573,609.6 -2.594326723,50.9820098563,609.6 -2.5906967097,50.9851077091,609.6 -2.5875356765,50.9884041042,609.6 -2.5848707832,50.991870825,609.6 -2.5827249586,50.9954781906,609.6 -2.581116701,50.9991953089,609.6 -2.5800599161,51.0029903407,609.6 -2.5795637937,51.0068307715,609.6 -2.5796327246,51.0106836897,609.6 -2.5802662577,51.0145160689,609.6 -2.5814590998,51.0182950504,609.6 -2.5832011558,51.0219882257,609.6 -2.5854776109,51.0255639143,609.6 -2.5882690536,51.0289914368,609.6 -2.5915516385,51.0322413781,609.6 -2.5952972881,51.0352858415,609.6 -2.5994739312,51.0380986885,609.6 -2.6040457767,51.0406557648,609.6 -2.60897362,51.0429351086,609.6 -2.6142151797,51.0449171406,609.6 -2.6197254613,51.0465848329,609.6 -2.6254571452,51.0479238563,609.6 -2.6313609955,51.0489227048,609.6 -2.6373862853,51.0495727947,609.6 -2.643481236,51.049868539,609.6 -2.6495934654,51.0498073961,609.6 -2.6556704418,51.0493898914,609.6 -2.6616599388,51.0486196131,609.6 -2.6675104878,51.0475031808,609.6 -2.6731718236,51.0460501886,609.6 -2.6785953191,51.0442731215,609.6 -2.6837344058,51.0421872477,609.6 -2.6885449756,51.0398104864,609.6 -2.6929857609,51.0371632529,609.6 -2.6970186893,51.0342682818,609.6 -2.7006092105,51.0311504313,609.6 -2.7037265914,51.0278364679,609.6 -2.7063441786,51.0243548361,609.6 -2.708439624,51.0207354127,609.6 -2.7099950736,51.0170092504,609.6 -2.7109973165,51.0132083097,609.6 -2.7114378947,51.0093651849,609.6 -2.7113131703,51.0055128239,609.6 -2.7106243521,51.0016842458,609.6 -2.7093774809,50.9979122577,609.6 -2.7075833724,50.994229174,609.6 -2.7052575206,50.9906665399,609.6 -2.7024199611,50.9872548621,609.6 -2.6990950954,50.9840233479,609.6 -2.6953114796,50.9809996566,609.6 -2.6911015776,50.9782096634,609.6 -2.6865014817,50.9756772394,609.6 -2.6815506027,50.9734240479,609.6 -2.6762913333,50.9714693611,609.6 + + + + + + EGRU107B YEOVILTON RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7784" txt_name="YEOVILTON RWY 04"><tr><td>505754N 0024053W -<br/>505814N 0024134W -<br/>505832N 0024111W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to<br/>505817N 0024035W -<br/>505817N 0024026W -<br/>505754N 0024053W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6813681667,50.9650763611,609.6 -2.6739531389,50.9712873611,609.6 -2.6762913333,50.9714693611,609.6 -2.6815638587,50.9734295096,609.6 -2.6865262778,50.9756896667,609.6 -2.6927310556,50.9704911944,609.6 -2.6813681667,50.9650763611,609.6 + + + + + + EGRU107C YEOVILTON RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7689" txt_name="YEOVILTON RWY 22"><tr><td>510310N 0023540W -<br/>510250N 0023459W -<br/>510210N 0023547W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to<br/>510232N 0023626W -<br/>510310N 0023540W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5943472222,51.0527433889,609.6 -2.6070863889,51.0421141111,609.6 -2.6033052479,51.0402731247,609.6 -2.5997455139,51.0382644429,609.6 -2.5964258333,51.0360986111,609.6 -2.5829642222,51.0473286111,609.6 -2.5943472222,51.0527433889,609.6 + + + + + + EGRU107D YEOVILTON RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7753" txt_name="YEOVILTON RWY 08"><tr><td>505950N 0024354W -<br/>510022N 0024400W -<br/>510028N 0024241W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to<br/>505956N 0024235W -<br/>505950N 0024354W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7315610556,50.9971264722,609.6 -2.7097279722,50.9988129167,609.6 -2.7106431331,51.0017583572,609.6 -2.7112195574,51.0047377531,609.6 -2.7114541944,51.0077356111,609.6 -2.7332775556,51.0060498889,609.6 -2.7315610556,50.9971264722,609.6 + + + + + + EGRU107E YEOVILTON RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7909" txt_name="YEOVILTON RWY 26"><tr><td>510110N 0023334W -<br/>510038N 0023328W -<br/>510032N 0023446W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to<br/>510104N 0023452W -<br/>510110N 0023334W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5594051667,51.019364,609.6 -2.5812353056,51.017707,609.6 -2.5803261568,51.0147607937,609.6 -2.5797560879,51.0117809128,609.6 -2.579528,51.0087828611,609.6 -2.5576881667,51.0104406111,609.6 -2.5594051667,51.019364,609.6 + + + + + + EGRU108 PORT OF DOVER + <table border="1" cellpadding="1" cellspacing="0" row_id="4894" txt_name="PORT OF DOVER"><tr><td>510907N 0012206E thence clockwise by the arc of a circle radius 2.25 NM centred on 510800N 0011900E to<br/>510656N 0011551E -<br/>510907N 0012206E <br/>Upper limit: 1000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>Flight permitted by any unmanned aircraft:<br/>operating in the service of the Port of Dover Police;<br/>operating in the service of the Kent Police;<br/>operating in the service of Kent Fire and Rescue Service; or<br/>operating with the permission of the Port of Dover Police.<br/><br/>SI 1329/2019.<br/><br/>Contact: Refer to Statutory Instrument.<br/><br/></td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.3683333333,51.1519444444,304.8 1.2641666667,51.1155555556,304.8 1.2672038795,51.1125068064,304.8 1.270605115,51.1096190712,304.8 1.2744300642,51.1069497853,304.8 1.2786434752,51.1045235011,304.8 1.2832065412,51.1023625326,304.8 1.2880772581,51.1004867505,304.8 1.2932108101,51.098913401,304.8 1.2985599804,51.0976569483,304.8 1.304075583,51.096728942,304.8 1.309706913,51.096137912,304.8 1.3154022092,51.0958892907,304.8 1.3211091266,51.095985363,304.8 1.3267752144,51.096425246,304.8 1.3323483941,51.0972048968,304.8 1.3377774353,51.0983171491,304.8 1.3430124231,51.0997517792,304.8 1.3480052141,51.1014955989,304.8 1.3527098772,51.1035325759,304.8 1.357083114,51.1058439808,304.8 1.3610846561,51.1084085577,304.8 1.3646776353,51.1112027189,304.8 1.3678289231,51.1142007606,304.8 1.3705094373,51.1173750984,304.8 1.3726944115,51.1206965203,304.8 1.3743636256,51.1241344542,304.8 1.375501596,51.1276572486,304.8 1.3760977216,51.1312324636,304.8 1.3761463859,51.1348271693,304.8 1.3756470134,51.1384082484,304.8 1.3746040794,51.1419427016,304.8 1.3730270737,51.1453979519,304.8 1.3709304173,51.1487421452,304.8 1.3683333333,51.1519444444,304.8 + + + + + + EGRU109A GLOUCESTERSHIRE + <table border="1" cellpadding="1" cellspacing="0" row_id="7725" txt_name="GLOUCESTERSHIRE"><tr><td>A circle, 2 NM radius, centred at 515339N 0021002W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1672222222,51.9274563633,609.6 -2.172758683,51.9272797941,609.6 -2.1782363268,51.9267519623,609.6 -2.1835969655,51.9258784752,609.6 -2.1887836621,51.9246686117,609.6 -2.1937413388,51.9231352228,609.6 -2.1984173653,51.9212945947,609.6 -2.2027621196,51.9191662747,609.6 -2.2067295166,51.9167728622,609.6 -2.2102774978,51.9141397679,609.6 -2.2133684771,51.9112949423,609.6 -2.2159697386,51.9082685781,609.6 -2.2180537808,51.9050927885,609.6 -2.2195986054,51.9018012655,609.6 -2.2205879463,51.8984289213,609.6 -2.2210114378,51.8950115175,609.6 -2.2208647187,51.8915852855,609.6 -2.2201494737,51.8881865421,609.6 -2.2188734096,51.8848513047,609.6 -2.2170501689,51.8816149097,609.6 -2.2146991796,51.8785116391,609.6 -2.2118454455,51.8755743577,609.6 -2.2085192775,51.8728341663,609.6 -2.2047559697,51.8703200735,609.6 -2.2005954239,51.8680586897,609.6 -2.1960817261,51.8660739467,609.6 -2.19126268,51.8643868459,609.6 -2.186189302,51.8630152369,609.6 -2.1809152833,51.8619736299,609.6 -2.1754964243,51.8612730433,609.6 -2.1699900479,51.8609208876,609.6 -2.1644543965,51.8609208876,609.6 -2.1589480201,51.8612730433,609.6 -2.1535291612,51.8619736299,609.6 -2.1482551424,51.8630152369,609.6 -2.1431817645,51.8643868459,609.6 -2.1383627184,51.8660739467,609.6 -2.1338490206,51.8680586897,609.6 -2.1296884748,51.8703200735,609.6 -2.125925167,51.8728341663,609.6 -2.122598999,51.8755743577,609.6 -2.1197452649,51.8785116391,609.6 -2.1173942755,51.8816149097,609.6 -2.1155710348,51.8848513047,609.6 -2.1142949708,51.8881865421,609.6 -2.1135797258,51.8915852855,609.6 -2.1134330067,51.8950115175,609.6 -2.1138564981,51.8984289213,609.6 -2.1148458391,51.9018012655,609.6 -2.1163906636,51.9050927885,609.6 -2.1184747058,51.9082685781,609.6 -2.1210759673,51.9112949423,609.6 -2.1241669467,51.9141397679,609.6 -2.1277149279,51.9167728622,609.6 -2.1316823249,51.9191662747,609.6 -2.1360270792,51.9212945947,609.6 -2.1407031056,51.9231352228,609.6 -2.1456607824,51.9246686117,609.6 -2.1508474789,51.9258784752,609.6 -2.1562081177,51.9267519623,609.6 -2.1616857614,51.9272797941,609.6 -2.1672222222,51.9274563633,609.6 + + + + + + EGRU109B GLOUCESTERSHIRE RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7686" txt_name="GLOUCESTERSHIRE RWY 04"><tr><td>515057N 0021212W -<br/>515115N 0021255W -<br/>515204N 0021200W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515148N 0021115W -<br/>515057N 0021212W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2033861111,51.8490638889,609.6 -2.1874931944,51.8633313889,609.6 -2.191914972,51.8645919882,609.6 -2.1961347567,51.8660948525,609.6 -2.200118,51.8678276944,609.6 -2.2153277778,51.8541694444,609.6 -2.2033861111,51.8490638889,609.6 + + + + + + EGRU109C GLOUCESTERSHIRE RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="8180" txt_name="GLOUCESTERSHIRE RWY 22"><tr><td>515605N 0020732W -<br/>515547N 0020648W -<br/>515501N 0020740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515521N 0020821W -<br/>515605N 0020732W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1254277778,51.93475,609.6 -2.1390743333,51.9225411667,609.6 -2.1350394219,51.9208495231,609.6 -2.1312688435,51.9189390143,609.6 -2.1277935278,51.9168253333,609.6 -2.1134611111,51.9296444444,609.6 -2.1254277778,51.93475,609.6 + + + + + + EGRU109D GLOUCESTERSHIRE RWY 04G + <table border="1" cellpadding="1" cellspacing="0" row_id="7757" txt_name="GLOUCESTERSHIRE RWY 04G"><tr><td>515105N 0021200W -<br/>515123N 0021243W -<br/>515203N 0021158W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515147N 0021112W -<br/>515105N 0021200W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1998861111,51.8513694444,609.6 -2.1867024167,51.86313675,609.6 -2.1911634416,51.8643562518,609.6 -2.1954279461,51.8658207904,609.6 -2.1994608889,51.8675183611,609.6 -2.2118055556,51.8564972222,609.6 -2.1998861111,51.8513694444,609.6 + + + + + + EGRU109E GLOUCESTERSHIRE RWY 22G + <table border="1" cellpadding="1" cellspacing="0" row_id="7801" txt_name="GLOUCESTERSHIRE RWY 22G"><tr><td>515557N 0020735W -<br/>515539N 0020652W -<br/>515459N 0020737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515520N 0020817W -<br/>515557N 0020735W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1264444444,51.9325694444,609.6 -2.13813,51.9221743611,609.6 -2.1341466733,51.9204284823,609.6 -2.1304358591,51.9184665182,609.6 -2.1270280833,51.9163046389,609.6 -2.1145027778,51.9274444444,609.6 -2.1264444444,51.9325694444,609.6 + + + + + + EGRU109F GLOUCESTERSHIRE RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7935" txt_name="GLOUCESTERSHIRE RWY 09"><tr><td>515302N 0021455W -<br/>515335N 0021500W -<br/>515342N 0021316W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515310N 0021310W -<br/>515302N 0021455W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.248525,51.8840111111,609.6 -2.2193798056,51.8860011667,609.6 -2.2203588823,51.8889439051,609.6 -2.2209052777,51.8919292781,609.6 -2.2210144722,51.8949329722,609.6 -2.2501027778,51.8929472222,609.6 -2.248525,51.8840111111,609.6 + + + + + + EGRU109G GLOUCESTERSHIRE RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7999" txt_name="GLOUCESTERSHIRE RWY 27"><tr><td>515414N 0020522W -<br/>515342N 0020517W -<br/>515335N 0020648W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to<br/>515408N 0020654W -<br/>515414N 0020522W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0895777778,51.9038138889,609.6 -2.1149658333,51.9021101667,609.6 -2.1140228124,51.8991634474,609.6 -2.1135131055,51.8961761338,609.6 -2.1134407778,51.8931725556,609.6 -2.0879944444,51.8948805556,609.6 -2.0895777778,51.9038138889,609.6 + + + + + + EGRU110A KEMBLE + <table border="1" cellpadding="1" cellspacing="0" row_id="7716" txt_name="KEMBLE"><tr><td>A circle, 2 NM radius, centred at 514005N 0020325W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0570083333,51.7013520953,609.6 -2.0625171561,51.7011755203,609.6 -2.0679674566,51.7006476712,609.6 -2.0733013381,51.6997741554,609.6 -2.0784621486,51.6985642518,609.6 -2.0833950862,51.6970308118,609.6 -2.0880477837,51.6951901218,609.6 -2.0923708672,51.6930617294,609.6 -2.0963184816,51.6906682346,609.6 -2.0998487782,51.6880350485,609.6 -2.1029243581,51.6851901223,609.6 -2.1055126678,51.6821636495,609.6 -2.1075863423,51.6789877442,609.6 -2.109123492,51.6756960994,609.6 -2.1101079308,51.6723236283,609.6 -2.1105293431,51.6689060938,609.6 -2.1103833884,51.6654797288,609.6 -2.1096717414,51.6620808513,609.6 -2.1084020693,51.6587454803,609.6 -2.1065879451,51.6555089538,609.6 -2.104248699,51.6524055552,609.6 -2.1014092092,51.6494681512,609.6 -2.0980996349,51.646727844,609.6 -2.0943550938,51.6442136437,609.6 -2.0902152886,51.6419521623,609.6 -2.0857240857,51.6399673329,609.6 -2.0809290509,51.6382801581,609.6 -2.0758809469,51.6369084885,609.6 -2.0706331981,51.6358668353,609.6 -2.065241328,51.6351662175,609.6 -2.0597623748,51.6348140461,609.6 -2.0542542919,51.6348140461,609.6 -2.0487753386,51.6351662175,609.6 -2.0433834685,51.6358668353,609.6 -2.0381357198,51.6369084885,609.6 -2.0330876158,51.6382801581,609.6 -2.028292581,51.6399673329,609.6 -2.0238013781,51.6419521623,609.6 -2.0196615729,51.6442136437,609.6 -2.0159170318,51.646727844,609.6 -2.0126074574,51.6494681512,609.6 -2.0097679677,51.6524055552,609.6 -2.0074287216,51.6555089538,609.6 -2.0056145974,51.6587454803,609.6 -2.0043449253,51.6620808513,609.6 -2.0036332783,51.6654797288,609.6 -2.0034873235,51.6689060938,609.6 -2.0039087359,51.6723236283,609.6 -2.0048931747,51.6756960994,609.6 -2.0064303243,51.6789877442,609.6 -2.0085039989,51.6821636495,609.6 -2.0110923086,51.6851901223,609.6 -2.0141678885,51.6880350485,609.6 -2.0176981851,51.6906682346,609.6 -2.0216457995,51.6930617294,609.6 -2.0259688829,51.6951901218,609.6 -2.0306215804,51.6970308118,609.6 -2.035554518,51.6985642518,609.6 -2.0407153286,51.6997741554,609.6 -2.0460492101,51.7006476712,609.6 -2.0514995105,51.7011755203,609.6 -2.0570083333,51.7013520953,609.6 + + + + + + EGRU110B KEMBLE RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="8007" txt_name="KEMBLE RWY 08"><tr><td>513918N 0020819W -<br/>513950N 0020828W -<br/>514001N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to<br/>513929N 0020629W -<br/>513918N 0020819W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1386894444,51.6548986944,609.6 -2.1081021667,51.6581286111,609.6 -2.1093354747,51.6610331599,609.6 -2.1101428888,51.6639950203,609.6 -2.11051775,51.6669900833,609.6 -2.1410953889,51.6637611389,609.6 -2.1386894444,51.6548986944,609.6 + + + + + + EGRU110C KEMBLE RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7585" txt_name="KEMBLE RWY 26"><tr><td>514052N 0015832W -<br/>514020N 0015823W -<br/>514009N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to<br/>514041N 0020021W -<br/>514052N 0015832W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9754756111,51.6811496667,609.6 -2.0058937778,51.6779745556,609.6 -2.0046661483,51.675069011,609.6 -2.0038649379,51.672106485,609.6 -2.0034965833,51.6691111111,609.6 -1.97306875,51.67228725,609.6 -1.9754756111,51.6811496667,609.6 + + + + + + EGRU110D KEMBLE RWY 08G + <table border="1" cellpadding="1" cellspacing="0" row_id="7975" txt_name="KEMBLE RWY 08G"><tr><td>513924N 0020746W -<br/>513956N 0020755W -<br/>514004N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to<br/>513932N 0020630W -<br/>513924N 0020746W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1295,51.6566277778,609.6 -2.1084556667,51.6588605,609.6 -2.1095817412,51.661782657,609.6 -2.1102796614,51.664756054,609.6 -2.1105436667,51.6677564722,609.6 -2.1319166667,51.6654888889,609.6 -2.1295,51.6566277778,609.6 + + + + + + EGRU110E KEMBLE RWY 26G + <table border="1" cellpadding="1" cellspacing="0" row_id="8191" txt_name="KEMBLE RWY 26G"><tr><td>514053N 0015853W -<br/>514021N 0015844W -<br/>514012N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to<br/>514044N 0020023W -<br/>514053N 0015853W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9814111111,51.6813694444,609.6 -2.0063030556,51.6787570556,609.6 -2.0049599261,51.6758704389,609.6 -2.0040410911,51.6729202744,609.6 -2.0035539444,51.6699306111,609.6 -1.9789916667,51.6725083333,609.6 -1.9814111111,51.6813694444,609.6 + + + + + + EGRU111A FAIRFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="7516" txt_name="FAIRFORD"><tr><td>A circle, 2.5 NM radius, centred at 514101N 0014724W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7900055556,51.7251302571,609.6 -1.7961881038,51.7249525789,609.6 -1.8023177604,51.7244210644,609.6 -1.80834209,51.7235402605,609.6 -1.8142095653,51.7223177018,609.6 -1.8198700117,51.7207638457,609.6 -1.8252750386,51.7188919822,609.6 -1.8303784562,51.7167181193,609.6 -1.8351366718,51.7142608454,609.6 -1.8395090636,51.711541169,609.6 -1.8434583283,51.7085823379,609.6 -1.846950799,51.7054096398,609.6 -1.8499567317,51.7020501846,609.6 -1.8524505575,51.6985326718,609.6 -1.8544110975,51.6948871446,609.6 -1.8558217409,51.691144732,609.6 -1.8566705822,51.6873373829,609.6 -1.8569505185,51.6834975923,609.6 -1.8566593054,51.679658124,609.6 -1.8557995713,51.6758517307,609.6 -1.8543787901,51.6721108749,609.6 -1.8524092124,51.6684674524,609.6 -1.8499077569,51.6649525207,609.6 -1.8468958622,51.6615960349,609.6 -1.8433993005,51.6584265935,609.6 -1.8394479548,51.6554711955,609.6 -1.8350755629,51.6527550116,609.6 -1.8303194283,51.6503011708,609.6 -1.8252201018,51.6481305646,609.6 -1.8198210368,51.6462616706,609.6 -1.8141682202,51.6447103955,609.6 -1.8083097825,51.6434899415,609.6 -1.8022955908,51.6426106944,609.6 -1.796176827,51.6420801356,609.6 -1.7900055556,51.6419027797,609.6 -1.7838342841,51.6420801356,609.6 -1.7777155203,51.6426106944,609.6 -1.7717013286,51.6434899415,609.6 -1.7658428909,51.6447103955,609.6 -1.7601900743,51.6462616706,609.6 -1.7547910093,51.6481305646,609.6 -1.7496916828,51.6503011708,609.6 -1.7449355482,51.6527550116,609.6 -1.7405631563,51.6554711955,609.6 -1.7366118107,51.6584265935,609.6 -1.7331152489,51.6615960349,609.6 -1.7301033542,51.6649525207,609.6 -1.7276018987,51.6684674524,609.6 -1.725632321,51.6721108749,609.6 -1.7242115398,51.6758517307,609.6 -1.7233518057,51.679658124,609.6 -1.7230605927,51.6834975923,609.6 -1.7233405289,51.6873373829,609.6 -1.7241893702,51.691144732,609.6 -1.7256000136,51.6948871446,609.6 -1.7275605536,51.6985326718,609.6 -1.7300543794,51.7020501846,609.6 -1.7330603121,51.7054096398,609.6 -1.7365527828,51.7085823379,609.6 -1.7405020475,51.711541169,609.6 -1.7448744393,51.7142608454,609.6 -1.7496326549,51.7167181193,609.6 -1.7547360725,51.7188919822,609.6 -1.7601410994,51.7207638457,609.6 -1.7658015458,51.7223177018,609.6 -1.7716690211,51.7235402605,609.6 -1.7776933507,51.7244210644,609.6 -1.7838230073,51.7249525789,609.6 -1.7900055556,51.7251302571,609.6 + + + + + + EGRU111B FAIRFORD RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8035" txt_name="FAIRFORD RWY 09"><tr><td>514037N 0015302W -<br/>514110N 0015304W -<br/>514112N 0015124W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to<br/>514039N 0015123W -<br/>514037N 0015302W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8839879444,51.6769958333,609.6 -1.8562672222,51.6776048333,609.6 -1.85678249,51.6805888471,609.6 -1.8569504954,51.6835881858,609.6 -1.8567703056,51.68658725,609.6 -1.8844827222,51.6859784444,609.6 -1.8839879444,51.6769958333,609.6 + + + + + + EGRU111C FAIRFORD RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="8053" txt_name="FAIRFORD RWY 27"><tr><td>514124N 0014146W -<br/>514052N 0014144W -<br/>514050N 0014324W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to<br/>514122N 0014325W -<br/>514124N 0014146W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6959973611,51.6899902222,609.6 -1.7237330278,51.6894188889,609.6 -1.7232232057,51.686434517,609.6 -1.7230607719,51.683435067,609.6 -1.7232465278,51.6804361389,609.6 -1.6955025278,51.6810076389,609.6 -1.6959973611,51.6899902222,609.6 + + + + + + EGRU112A NETHERAVON + <table border="1" cellpadding="1" cellspacing="0" row_id="7770" txt_name="NETHERAVON"><tr><td>A circle, 2 NM radius, centred at 511453N 0014517W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7548361111,51.2813878265,609.6 -1.7602945509,51.2812112407,609.6 -1.7656950054,51.2806833593,609.6 -1.7709801093,51.2798097898,609.6 -1.7760937305,51.2785998114,609.6 -1.7809815694,51.2770662759,609.6 -1.7855917388,51.2752254703,609.6 -1.7898753167,51.2730969429,609.6 -1.7937868678,51.2707032944,609.6 -1.7972849255,51.268069937,609.6 -1.8003324321,51.2652248232,609.6 -1.8028971307,51.262198148,609.6 -1.8049519048,51.259022027,609.6 -1.8064750628,51.255730155,609.6 -1.8074505644,51.2523574476,609.6 -1.807868186,51.2489396698,609.6 -1.807723624,51.2455130569,609.6 -1.8070185356,51.2421139298,609.6 -1.8057605153,51.2387783101,609.6 -1.80396301,51.2355415388,609.6 -1.8016451713,51.2324379023,609.6 -1.7988316485,51.2295002701,609.6 -1.7955523241,51.2267597475,609.6 -1.7918419943,51.2242453475,609.6 -1.7877399989,51.2219836846,609.6 -1.7832898041,51.2199986946,609.6 -1.7785385418,51.2183113821,609.6 -1.7735365123,51.2169396,609.6 -1.7683366538,51.2158978609,609.6 -1.7629939845,51.2151971852,609.6 -1.7575650239,51.2148449846,609.6 -1.7521071983,51.2148449846,609.6 -1.7466782377,51.2151971852,609.6 -1.7413355684,51.2158978609,609.6 -1.7361357099,51.2169396,609.6 -1.7311336805,51.2183113821,609.6 -1.7263824182,51.2199986946,609.6 -1.7219322233,51.2219836846,609.6 -1.717830228,51.2242453475,609.6 -1.7141198982,51.2267597475,609.6 -1.7108405737,51.2295002701,609.6 -1.7080270509,51.2324379023,609.6 -1.7057092122,51.2355415388,609.6 -1.7039117069,51.2387783101,609.6 -1.7026536866,51.2421139298,609.6 -1.7019485982,51.2455130569,609.6 -1.7018040362,51.2489396698,609.6 -1.7022216578,51.2523574476,609.6 -1.7031971595,51.255730155,609.6 -1.7047203175,51.259022027,609.6 -1.7067750915,51.262198148,609.6 -1.7093397901,51.2652248232,609.6 -1.7123872968,51.268069937,609.6 -1.7158853544,51.2707032944,609.6 -1.7197969055,51.2730969429,609.6 -1.7240804834,51.2752254703,609.6 -1.7286906528,51.2770662759,609.6 -1.7335784917,51.2785998114,609.6 -1.7386921129,51.2798097898,609.6 -1.7439772169,51.2806833593,609.6 -1.7493776714,51.2812112407,609.6 -1.7548361111,51.2813878265,609.6 + + + + + + EGRU112B NETHERAVON RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7542" txt_name="NETHERAVON RWY 04"><tr><td>511235N 0014751W -<br/>511255N 0014830W -<br/>511333N 0014739W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to<br/>511312N 0014700W -<br/>511235N 0014751W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7974191944,51.2095862778,609.6 -1.7833475,51.22002175,609.6 -1.7872618918,51.2217490699,609.6 -1.7909127083,51.2236908183,609.6 -1.7942702222,51.2258312222,609.6 -1.8083353333,51.2153988056,609.6 -1.7974191944,51.2095862778,609.6 + + + + + + EGRU112C NETHERAVON RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7956" txt_name="NETHERAVON RWY 22"><tr><td>511718N 0014235W -<br/>511657N 0014156W -<br/>511613N 0014255W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to<br/>511634N 0014335W -<br/>511718N 0014235W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7097918611,51.2883559167,609.6 -1.7262928889,51.2761612222,609.6 -1.7223759775,51.2744320342,609.6 -1.7187238237,51.27248831,609.6 -1.7153661944,51.2703458889,609.6 -1.6988584444,51.2825434722,609.6 -1.7097918611,51.2883559167,609.6 + + + + + + EGRU112D NETHERAVON RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7788" txt_name="NETHERAVON RWY 11"><tr><td>511535N 0014957W -<br/>511605N 0014941W -<br/>511546N 0014809W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to<br/>511515N 0014825W -<br/>511535N 0014957W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8324731944,51.2596027222,609.6 -1.8069665833,51.25427375,609.6 -1.8058682165,51.2571979427,609.6 -1.8043540669,51.2600480825,609.6 -1.8024363889,51.2628009444,609.6 -1.8279352222,51.2681283889,609.6 -1.8324731944,51.2596027222,609.6 + + + + + + EGRU112E NETHERAVON RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7789" txt_name="NETHERAVON RWY 29"><tr><td>511412N 0014038W -<br/>511341N 0014054W -<br/>511400N 0014226W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to<br/>511431N 0014210W -<br/>511412N 0014038W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6772466667,51.2365466389,609.6 -1.7027167778,51.2419014167,609.6 -1.7038199435,51.2389779812,609.6 -1.7053382967,51.2361288557,609.6 -1.7072593889,51.2333772222,609.6 -1.6817815278,51.2280209167,609.6 -1.6772466667,51.2365466389,609.6 + + + + + + EGRU113A BOSCOMBE + <table border="1" cellpadding="1" cellspacing="0" row_id="7845" txt_name="BOSCOMBE"><tr><td>A circle, 2.5 NM radius, centred at 510912N 0014504W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7510111111,51.194925709,609.6 -1.7571224367,51.1947480177,609.6 -1.7631814827,51.1942164639,609.6 -1.7691364201,51.1933355946,609.6 -1.774936318,51.1921129447,609.6 -1.7805315813,51.1905589717,609.6 -1.7858743789,51.1886869661,609.6 -1.790919054,51.1865129364,609.6 -1.7956225166,51.1840554715,609.6 -1.799944613,51.1813355807,609.6 -1.8038484688,51.178376513,609.6 -1.8073008037,51.1752035572,609.6 -1.8102722147,51.1718438244,609.6 -1.812737425,51.1683260161,609.6 -1.814675497,51.1646801771,609.6 -1.8160700079,51.1609374388,609.6 -1.8169091861,51.1571297523,609.6 -1.8171860069,51.1532896154,609.6 -1.8168982483,51.1494497946,609.6 -1.8160485048,51.1456430459,609.6 -1.8146441607,51.141901835,609.6 -1.8126973227,51.1382580611,609.6 -1.8102247121,51.1347427851,609.6 -1.8072475184,51.1313859657,609.6 -1.8037912153,51.1282162051,609.6 -1.7998853411,51.1252605058,609.6 -1.7955632448,51.1225440417,609.6 -1.7908618005,51.1200899451,609.6 -1.7858210936,51.1179191107,609.6 -1.7804840787,51.1160500185,609.6 -1.7748962157,51.1144985778,609.6 -1.7691050838,51.1132779929,609.6 -1.7631599794,51.112398651,609.6 -1.7571114989,51.111868035,609.6 -1.7510111111,51.1116906599,609.6 -1.7449107234,51.111868035,609.6 -1.7388622428,51.112398651,609.6 -1.7329171384,51.1132779929,609.6 -1.7271260066,51.1144985778,609.6 -1.7215381435,51.1160500185,609.6 -1.7162011287,51.1179191107,609.6 -1.7111604217,51.1200899451,609.6 -1.7064589775,51.1225440417,609.6 -1.7021368811,51.1252605058,609.6 -1.6982310069,51.1282162051,609.6 -1.6947747038,51.1313859657,609.6 -1.6917975101,51.1347427851,609.6 -1.6893248995,51.1382580611,609.6 -1.6873780615,51.141901835,609.6 -1.6859737175,51.1456430459,609.6 -1.6851239739,51.1494497946,609.6 -1.6848362153,51.1532896154,609.6 -1.6851130361,51.1571297523,609.6 -1.6859522143,51.1609374388,609.6 -1.6873467253,51.1646801771,609.6 -1.6892847972,51.1683260161,609.6 -1.6917500075,51.1718438244,609.6 -1.6947214185,51.1752035572,609.6 -1.6981737535,51.178376513,609.6 -1.7020776092,51.1813355807,609.6 -1.7063997056,51.1840554715,609.6 -1.7111031682,51.1865129364,609.6 -1.7161478433,51.1886869661,609.6 -1.7214906409,51.1905589717,609.6 -1.7270859043,51.1921129447,609.6 -1.7328858021,51.1933355946,609.6 -1.7388407396,51.1942164639,609.6 -1.7448997855,51.1947480177,609.6 -1.7510111111,51.194925709,609.6 + + + + + + EGRU113B BOSCOMBE RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7971" txt_name="BOSCOMBE RWY 05"><tr><td>510643N 0014908W -<br/>510707N 0014941W -<br/>510749N 0014822W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>510724N 0014749W -<br/>510643N 0014908W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8188315556,51.1118148056,609.6 -1.7969201389,51.12334375,609.6 -1.8002337125,51.1255025611,609.6 -1.8032917451,51.127805952,609.6 -1.8060783056,51.1302419722,609.6 -1.8279827222,51.1187155278,609.6 -1.8188315556,51.1118148056,609.6 + + + + + + EGRU113C BOSCOMBE RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="8047" txt_name="BOSCOMBE RWY 23"><tr><td>511139N 0014103W -<br/>511114N 0014030W -<br/>511035N 0014145W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>511100N 0014218W -<br/>511139N 0014103W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6841814444,51.19420625,609.6 -1.7050659722,51.1832688889,609.6 -1.7017510046,51.1811084272,609.6 -1.6986927047,51.1788033417,609.6 -1.6959069722,51.1763656389,609.6 -1.6750153333,51.1873056111,609.6 -1.6841814444,51.19420625,609.6 + + + + + + EGRU113D BOSCOMBE RWY 05N + <table border="1" cellpadding="1" cellspacing="0" row_id="8050" txt_name="BOSCOMBE RWY 05N"><tr><td>510706N 0014834W -<br/>510731N 0014907W -<br/>510753N 0014826W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>510727N 0014754W -<br/>510706N 0014834W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8093775,51.118341,609.6 -1.7982730833,51.1241878611,609.6 -1.8014879624,51.1264067992,609.6 -1.8044405247,51.1287657571,609.6 -1.8071153889,51.1312524722,609.6 -1.8185353056,51.1252389167,609.6 -1.8093775,51.118341,609.6 + + + + + + EGRU113E BOSCOMBE RWY 23N + <table border="1" cellpadding="1" cellspacing="0" row_id="7994" txt_name="BOSCOMBE RWY 23N"><tr><td>511114N 0014202W -<br/>511049N 0014129W -<br/>511039N 0014149W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>511103N 0014223W -<br/>511114N 0014202W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7004613056,51.1872856389,609.6 -1.7065058611,51.1841162222,609.6 -1.7030883915,51.1820178836,609.6 -1.6999208758,51.179770037,609.6 -1.6970197778,51.1773844167,609.6 -1.6912912222,51.1803878056,609.6 -1.7004613056,51.1872856389,609.6 + + + + + + EGRU113F BOSCOMBE RWY 05S + <table border="1" cellpadding="1" cellspacing="0" row_id="7557" txt_name="BOSCOMBE RWY 05S"><tr><td>510635N 0014909W -<br/>510700N 0014941W -<br/>510745N 0014817W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>510720N 0014743W -<br/>510635N 0014909W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8190288333,51.1098363889,609.6 -1.7952359444,51.12235775,609.6 -1.7986686484,51.1244440448,609.6 -1.8018536395,51.1266806071,609.6 -1.8047743333,51.1290558056,609.6 -1.8281826944,51.1167355,609.6 -1.8190288333,51.1098363889,609.6 + + + + + + EGRU113H BOSCOMBE RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7769" txt_name="BOSCOMBE RWY 17"><tr><td>511215N 0014526W -<br/>511223N 0014436W -<br/>511139N 0014419W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>511142N 0014513W -<br/>511215N 0014526W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7572530278,51.2042225833,609.6 -1.7536991944,51.1948913889,609.6 -1.7486860338,51.1949000253,609.6 -1.7436862295,51.1946701902,609.6 -1.7387285,51.1942031944,609.6 -1.743336,51.2063113333,609.6 -1.7572530278,51.2042225833,609.6 + + + + + + EGRU113I BOSCOMBE RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7737" txt_name="BOSCOMBE RWY 35"><tr><td>510608N 0014214W -<br/>510600N 0014304W -<br/>510656N 0014325W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to<br/>510713N 0014238W -<br/>510608N 0014214W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7037857778,51.1021631111,609.6 -1.7106696111,51.1203252222,609.6 -1.7147495861,51.1185007217,609.6 -1.7190368393,51.1168755177,609.6 -1.7235068333,51.1154588889,609.6 -1.7176715,51.1000743056,609.6 -1.7037857778,51.1021631111,609.6 + + + + + + EGRU114A THRUXTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7570" txt_name="THRUXTON"><tr><td>A circle, 2 NM radius, centred at 511240N 0013549W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5969805556,51.2445019264,609.6 -1.6024346282,51.2443253397,609.6 -1.6078307621,51.2437974554,609.6 -1.6131116381,51.2429238812,609.6 -1.618221169,51.2417138962,609.6 -1.6231050988,51.2401803523,609.6 -1.6277115819,51.2383395365,609.6 -1.6319917356,51.2362109971,609.6 -1.6359001607,51.2338173351,609.6 -1.6393954239,51.2311839626,609.6 -1.6424404972,51.2283388323,609.6 -1.6450031492,51.2253121392,609.6 -1.6470562849,51.2221359992,609.6 -1.6485782301,51.2188441073,609.6 -1.649552957,51.215471379,609.6 -1.64997025,51.2120535798,609.6 -1.6498258088,51.2086269452,609.6 -1.6491212888,51.2052277961,609.6 -1.6478642784,51.2018921545,609.6 -1.6460682136,51.1986553617,609.6 -1.6437522304,51.1955517043,609.6 -1.6409409584,51.192614052,609.6 -1.637664256,51.1898735105,609.6 -1.6339568916,51.1873590929,609.6 -1.6298581736,51.1850974141,609.6 -1.6254115333,51.1831124099,609.6 -1.6206640652,51.1814250854,609.6 -1.6156660294,51.1800532933,609.6 -1.6104703221,51.1790115467,609.6 -1.6051319175,51.1783108659,609.6 -1.5997072902,51.1779586627,609.6 -1.5942538209,51.1779586627,609.6 -1.5888291937,51.1783108659,609.6 -1.5834907891,51.1790115467,609.6 -1.5782950817,51.1800532933,609.6 -1.573297046,51.1814250854,609.6 -1.5685495778,51.1831124099,609.6 -1.5641029375,51.1850974141,609.6 -1.5600042195,51.1873590929,609.6 -1.5562968551,51.1898735105,609.6 -1.5530201527,51.192614052,609.6 -1.5502088807,51.1955517043,609.6 -1.5478928975,51.1986553617,609.6 -1.5460968327,51.2018921545,609.6 -1.5448398223,51.2052277961,609.6 -1.5441353023,51.2086269452,609.6 -1.5439908611,51.2120535798,609.6 -1.5444081541,51.215471379,609.6 -1.545382881,51.2188441073,609.6 -1.5469048262,51.2221359992,609.6 -1.5489579619,51.2253121392,609.6 -1.5515206139,51.2283388323,609.6 -1.5545656872,51.2311839626,609.6 -1.5580609505,51.2338173351,609.6 -1.5619693756,51.2362109971,609.6 -1.5662495292,51.2383395365,609.6 -1.5708560123,51.2401803523,609.6 -1.5757399421,51.2417138962,609.6 -1.580849473,51.2429238812,609.6 -1.586130349,51.2437974554,609.6 -1.5915264829,51.2443253397,609.6 -1.5969805556,51.2445019264,609.6 + + + + + + EGRU114B THRUXTON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7592" txt_name="THRUXTON RWY 07"><tr><td>511117N 0013954W -<br/>511147N 0014014W -<br/>511209N 0013853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to<br/>511139N 0013833W -<br/>511117N 0013954W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6649138889,51.1881222222,609.6 -1.6424814167,51.1941383889,609.6 -1.6447465308,51.1967841337,609.6 -1.6466230757,51.1995473688,609.6 -1.6480957222,51.2024056111,609.6 -1.6705194444,51.1963916667,609.6 -1.6649138889,51.1881222222,609.6 + + + + + + EGRU114C THRUXTON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7693" txt_name="THRUXTON RWY 25"><tr><td>511403N 0013144W -<br/>511334N 0013124W -<br/>511312N 0013245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to<br/>511342N 0013305W -<br/>511403N 0013144W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5288583333,51.2342861111,609.6 -1.5514453333,51.22825975,609.6 -1.5491841987,51.2256122627,609.6 -1.5473125872,51.2228475387,609.6 -1.5458456667,51.2199881111,609.6 -1.52325,51.2260166667,609.6 -1.5288583333,51.2342861111,609.6 + + + + + + EGRU114D THRUXTON RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="7581" txt_name="THRUXTON RWY 12"><tr><td>511357N 0014004W -<br/>511424N 0013936W -<br/>511354N 0013820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to<br/>511326N 0013846W -<br/>511357N 0014004W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6677805556,51.2325833333,609.6 -1.6460598611,51.2237947222,609.6 -1.6440514429,51.2265260821,609.6 -1.6416583054,51.2291324058,609.6 -1.6388999444,51.2315923889,609.6 -1.6600138889,51.2401361111,609.6 -1.6677805556,51.2325833333,609.6 + + + + + + EGRU114E THRUXTON RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="7715" txt_name="THRUXTON RWY 30"><tr><td>511116N 0013150W -<br/>511048N 0013218W -<br/>511118N 0013331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to<br/>511144N 0013301W -<br/>511116N 0013150W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5306666667,51.1876861111,609.6 -1.55016125,51.1956079444,609.6 -1.5525946413,51.193017224,609.6 -1.555389954,51.1905750191,609.6 -1.5585243611,51.18830125,609.6 -1.5384222222,51.1801333333,609.6 -1.5306666667,51.1876861111,609.6 + + + + + + EGRU115A BRIZE NORTON + <table border="1" cellpadding="1" cellspacing="0" row_id="8174" txt_name="BRIZE NORTON"><tr><td>A circle, 2.5 NM radius, centred at 514500N 0013459W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5829472222,51.7915992282,609.6 -1.5891388545,51.7914215516,609.6 -1.5952775171,51.790890042,609.6 -1.6013106972,51.7900092462,609.6 -1.6071867917,51.7887866989,609.6 -1.6128555517,51.7872328574,609.6 -1.6182685155,51.7853610116,609.6 -1.6233794253,51.7831871695,609.6 -1.6281446243,51.7807299195,609.6 -1.632523431,51.7780102697,609.6 -1.6364784872,51.7750514682,609.6 -1.6399760768,51.7718788023,609.6 -1.6429864125,51.7685193817,609.6 -1.6454838879,51.7650019058,609.6 -1.6474472935,51.7613564176,609.6 -1.6488599943,51.7576140457,609.6 -1.6497100679,51.7538067388,609.6 -1.6499904014,51.7499669915,609.6 -1.6496987476,51.7461275672,609.6 -1.6488377392,51.7423212184,609.6 -1.6474148615,51.7385804071,609.6 -1.6454423834,51.7349370286,609.6 -1.6429372489,51.7314221399,609.6 -1.6399209283,51.7280656959,609.6 -1.6364192318,51.7248962945,609.6 -1.6324620865,51.7219409343,609.6 -1.6280832799,51.7192247855,609.6 -1.6233201699,51.7167709767,609.6 -1.618213367,51.7146003992,609.6 -1.612806388,51.7127315299,609.6 -1.6071452871,51.7111802756,609.6 -1.6012782652,51.7099598381,609.6 -1.595255262,51.7090806028,609.6 -1.5891275342,51.7085500512,609.6 -1.5829472222,51.7083726977,609.6 -1.5767669102,51.7085500512,609.6 -1.5706391824,51.7090806028,609.6 -1.5646161793,51.7099598381,609.6 -1.5587491573,51.7111802756,609.6 -1.5530880564,51.7127315299,609.6 -1.5476810775,51.7146003992,609.6 -1.5425742745,51.7167709767,609.6 -1.5378111646,51.7192247855,609.6 -1.5334323579,51.7219409343,609.6 -1.5294752127,51.7248962945,609.6 -1.5259735161,51.7280656959,609.6 -1.5229571956,51.7314221399,609.6 -1.5204520611,51.7349370286,609.6 -1.518479583,51.7385804071,609.6 -1.5170567052,51.7423212184,609.6 -1.5161956968,51.7461275672,609.6 -1.515904043,51.7499669915,609.6 -1.5161843765,51.7538067388,609.6 -1.5170344501,51.7576140457,609.6 -1.518447151,51.7613564176,609.6 -1.5204105566,51.7650019058,609.6 -1.522908032,51.7685193817,609.6 -1.5259183676,51.7718788023,609.6 -1.5294159573,51.7750514682,609.6 -1.5333710135,51.7780102697,609.6 -1.5377498201,51.7807299195,609.6 -1.5425150191,51.7831871695,609.6 -1.5476259289,51.7853610116,609.6 -1.5530388928,51.7872328574,609.6 -1.5587076528,51.7887866989,609.6 -1.5645837472,51.7900092462,609.6 -1.5706169273,51.790890042,609.6 -1.5767555899,51.7914215516,609.6 -1.5829472222,51.7915992282,609.6 + + + + + + EGRU115B BRIZE NORTON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7665" txt_name="BRIZE NORTON RWY 07"><tr><td>514344N 0014017W -<br/>514415N 0014032W -<br/>514433N 0013856W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to<br/>514402N 0013841W -<br/>514344N 0014017W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6714538333,51.72900125,609.6 -1.6447841389,51.7339242778,609.6 -1.6464897503,51.736732361,609.6 -1.6478651552,51.7396094469,609.6 -1.6489031389,51.7425405833,609.6 -1.6755641667,51.7376190556,609.6 -1.6714538333,51.72900125,609.6 + + + + + + EGRU115C BRIZE NORTON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7857" txt_name="BRIZE NORTON RWY 25"><tr><td>514615N 0012940W -<br/>514544N 0012925W -<br/>514527N 0013101W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to<br/>514558N 0013116W -<br/>514615N 0012940W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4943830556,51.7709242778,609.6 -1.5210811389,51.7660371944,609.6 -1.5193796402,51.7632279118,609.6 -1.5180090481,51.7603498265,609.6 -1.5169764444,51.7574179167,609.6 -1.4902697222,51.7623065278,609.6 -1.4943830556,51.7709242778,609.6 + + + + + + EGRU116A MIDDLE WALLOP + <table border="1" cellpadding="1" cellspacing="0" row_id="7604" txt_name="MIDDLE WALLOP"><tr><td>A circle, 2 NM radius, centred at 510828N 0013422W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5726722222,51.1742773282,609.6 -1.5781180062,51.1741007397,609.6 -1.5835059398,51.17357285,609.6 -1.5887787912,51.1726992668,609.6 -1.5938805588,51.1714892692,609.6 -1.5987570692,51.1699557093,609.6 -1.6033565558,51.168114874,609.6 -1.6076302102,51.165986312,609.6 -1.6115327024,51.1635926242,609.6 -1.6150226618,51.1609592229,609.6 -1.6180631166,51.1581140612,609.6 -1.6206218842,51.1550873341,609.6 -1.6226719104,51.1519111579,609.6 -1.6241915537,51.1486192279,609.6 -1.6251648102,51.14524646,609.6 -1.6255814795,51.1418286201,609.6 -1.6254372673,51.1384019438,609.6 -1.6247338262,51.135002753,609.6 -1.6234787327,51.1316670697,609.6 -1.6216854019,51.1284302359,609.6 -1.6193729405,51.1253265386,609.6 -1.6165659404,51.1223888482,609.6 -1.6132942145,51.1196482706,609.6 -1.6095924784,51.1171338196,609.6 -1.6054999807,51.1148721104,609.6 -1.6010600869,51.1128870793,609.6 -1.59631982,51.1111997318,609.6 -1.5913293643,51.1098279209,609.6 -1.5861415357,51.10878616,609.6 -1.5808112254,51.1080854694,609.6 -1.5753948227,51.1077332614,609.6 -1.5699496217,51.1077332614,609.6 -1.564533219,51.1080854694,609.6 -1.5592029088,51.10878616,609.6 -1.5540150801,51.1098279209,609.6 -1.5490246244,51.1111997318,609.6 -1.5442843576,51.1128870793,609.6 -1.5398444637,51.1148721104,609.6 -1.535751966,51.1171338196,609.6 -1.5320502299,51.1196482706,609.6 -1.5287785041,51.1223888482,609.6 -1.525971504,51.1253265386,609.6 -1.5236590426,51.1284302359,609.6 -1.5218657117,51.1316670697,609.6 -1.5206106182,51.135002753,609.6 -1.5199071771,51.1384019438,609.6 -1.5197629649,51.1418286201,609.6 -1.5201796342,51.14524646,609.6 -1.5211528908,51.1486192279,609.6 -1.522672534,51.1519111579,609.6 -1.5247225603,51.1550873341,609.6 -1.5272813278,51.1581140612,609.6 -1.5303217826,51.1609592229,609.6 -1.5338117421,51.1635926242,609.6 -1.5377142342,51.165986312,609.6 -1.5419878886,51.168114874,609.6 -1.5465873752,51.1699557093,609.6 -1.5514638856,51.1714892692,609.6 -1.5565656532,51.1726992668,609.6 -1.5618385047,51.17357285,609.6 -1.5672264383,51.1741007397,609.6 -1.5726722222,51.1742773282,609.6 + + + + + + EGRU116B MIDDLE WALLOP RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7811" txt_name="MIDDLE WALLOP RWY 08"><tr><td>510812N 0013842W -<br/>510844N 0013847W -<br/>510849N 0013729W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to<br/>510816N 0013731W -<br/>510812N 0013842W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6450034167,51.1365355833,609.6 -1.6253642222,51.13786925,609.6 -1.6255978757,51.140904555,609.6 -1.6253905593,51.1439406175,609.6 -1.6247439722,51.1469521389,609.6 -1.6465238611,51.14547325,609.6 -1.6450034167,51.1365355833,609.6 + + + + + + EGRU116C MIDDLE WALLOP RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7617" txt_name="MIDDLE WALLOP RWY 26"><tr><td>510922N 0012924W -<br/>510849N 0012919W -<br/>510842N 0013112W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to<br/>510914N 0013126W -<br/>510922N 0012924W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4901112778,51.15600175,609.6 -1.52378725,51.153753,609.6 -1.5221410871,51.1508959449,609.6 -1.5209162238,51.1479563643,609.6 -1.5201227222,51.1449587778,609.6 -1.4885904722,51.1470641111,609.6 -1.4901112778,51.15600175,609.6 + + + + + + EGRU116D MIDDLE WALLOP RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7608" txt_name="MIDDLE WALLOP RWY 17"><tr><td>511125N 0013520W -<br/>511129N 0013429W -<br/>511027N 0013418W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to<br/>511024N 0013509W -<br/>511125N 0013520W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.588953,51.1903857222,609.6 -1.5857961667,51.1732382222,609.6 -1.5811173714,51.1738510424,609.6 -1.5763696609,51.1741960353,609.6 -1.5715917778,51.1742703889,609.6 -1.5747432222,51.1914171111,609.6 -1.588953,51.1903857222,609.6 + + + + + + EGRU116E MIDDLE WALLOP RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7675" txt_name="MIDDLE WALLOP RWY 35"><tr><td>510530N 0013323W -<br/>510526N 0013414W -<br/>510628N 0013426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to<br/>510631N 0013334W -<br/>510530N 0013323W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.556427,51.0915795,609.6 -1.5595671111,51.1087266944,609.6 -1.5642396379,51.1081147689,609.6 -1.5689806823,51.1077702969,609.6 -1.5737517222,51.1076960833,609.6 -1.5706061667,51.0905481111,609.6 -1.556427,51.0915795,609.6 + + + + + + EGRU117A OXFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="8136" txt_name="OXFORD"><tr><td>A circle, 2 NM radius, centred at 515013N 0011912W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.32,51.8702344667,609.6 -1.3255294318,51.870057896,609.6 -1.3310001216,51.8695300599,609.6 -1.3363539553,51.8686565655,609.6 -1.3415340685,51.8674466918,609.6 -1.3464854536,51.86591329,609.6 -1.351155547,51.8640726463,609.6 -1.3554947899,51.861944308,609.6 -1.3594571558,51.8595508747,609.6 -1.3630006394,51.8569177572,609.6 -1.3660877023,51.8540729061,609.6 -1.3686856699,51.8510465145,609.6 -1.3707670754,51.8478706957,609.6 -1.3723099481,51.8445791419,609.6 -1.3732980424,51.8412067656,609.6 -1.3737210051,51.8377893287,609.6 -1.3735744804,51.8343630631,609.6 -1.3728601504,51.8309642858,609.6 -1.371585712,51.8276290146,609.6 -1.3697647898,51.8243925863,609.6 -1.3674167871,51.8212892834,609.6 -1.3645666756,51.8183519709,609.6 -1.3612447278,51.8156117502,609.6 -1.3574861927,51.8130976302,609.6 -1.3533309217,51.8108362217,609.6 -1.3488229448,51.8088514569,609.6 -1.3440100053,51.8071643374,609.6 -1.3389430551,51.805792713,609.6 -1.3336757173,51.8047510943,609.6 -1.3282637222,51.8040504998,609.6 -1.3227643201,51.8036983402,609.6 -1.3172356799,51.8036983402,609.6 -1.3117362778,51.8040504998,609.6 -1.3063242827,51.8047510943,609.6 -1.3010569449,51.805792713,609.6 -1.2959899947,51.8071643374,609.6 -1.2911770552,51.8088514569,609.6 -1.2866690783,51.8108362217,609.6 -1.2825138073,51.8130976302,609.6 -1.2787552722,51.8156117502,609.6 -1.2754333244,51.8183519709,609.6 -1.2725832129,51.8212892834,609.6 -1.2702352102,51.8243925863,609.6 -1.268414288,51.8276290146,609.6 -1.2671398496,51.8309642858,609.6 -1.2664255196,51.8343630631,609.6 -1.2662789949,51.8377893287,609.6 -1.2667019576,51.8412067656,609.6 -1.2676900519,51.8445791419,609.6 -1.2692329246,51.8478706957,609.6 -1.2713143301,51.8510465145,609.6 -1.2739122977,51.8540729061,609.6 -1.2769993606,51.8569177572,609.6 -1.2805428442,51.8595508747,609.6 -1.2845052101,51.861944308,609.6 -1.288844453,51.8640726463,609.6 -1.2935145464,51.86591329,609.6 -1.2984659315,51.8674466918,609.6 -1.3036460447,51.8686565655,609.6 -1.3089998784,51.8695300599,609.6 -1.3144705682,51.870057896,609.6 -1.32,51.8702344667,609.6 + + + + + + EGRU117B OXFORD RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="7991" txt_name="OXFORD RWY 01"><tr><td>514710N 0011941W -<br/>514716N 0012032W -<br/>514819N 0012013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to<br/>514813N 0011922W -<br/>514710N 0011941W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3280333333,51.7861444444,609.6 -1.3226977778,51.80369625,609.6 -1.3275216808,51.8039822011,609.6 -1.3322844625,51.8045363966,609.6 -1.3369474167,51.8053543333,609.6 -1.342275,51.7878111111,609.6 -1.3280333333,51.7861444444,609.6 + + + + + + EGRU117C OXFORD RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="7506" txt_name="OXFORD RWY 19"><tr><td>515316N 0011843W -<br/>515310N 0011751W -<br/>515207N 0011811W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to<br/>515213N 0011902W -<br/>515316N 0011843W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3118583333,51.8877833333,609.6 -1.3172211389,51.8701899722,609.6 -1.3123911033,51.8698993105,609.6 -1.3076231617,51.8693401192,609.6 -1.3029562222,51.8685169444,609.6 -1.2975861111,51.8861166667,609.6 -1.3118583333,51.8877833333,609.6 + + + + + + EGRU118A BENSON + <table border="1" cellpadding="1" cellspacing="0" row_id="7758" txt_name="BENSON"><tr><td>A circle, 2 NM radius, centred at 513654N 0010545W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0958472222,51.6483301753,609.6 -1.1013496162,51.648153599,609.6 -1.1067935565,51.6476257459,609.6 -1.112121214,51.6467522233,609.6 -1.1172760033,51.6455423103,609.6 -1.1222031865,51.6440088582,609.6 -1.1268504575,51.6421681537,609.6 -1.1311685001,51.6400397443,609.6 -1.1351115129,51.6376462301,609.6 -1.1386376959,51.6350130224,609.6 -1.1417096938,51.6321680726,609.6 -1.1442949908,51.6291415743,609.6 -1.1463662537,51.6259656419,609.6 -1.1479016182,51.6226739684,609.6 -1.1488849166,51.6193014675,609.6 -1.1493058453,51.6158839024,609.6 -1.1491600683,51.6124575061,609.6 -1.1484492582,51.6090585972,609.6 -1.1471810729,51.6057231948,609.6 -1.1453690692,51.6024866374,609.6 -1.1430325547,51.5993832088,609.6 -1.1401963783,51.596445776,609.6 -1.1368906638,51.5937054416,609.6 -1.1331504879,51.5911912162,609.6 -1.1290155071,51.5889297119,609.6 -1.1245295367,51.5869448622,609.6 -1.1197400871,51.58525767,609.6 -1.1146978621,51.5838859862,609.6 -1.109456224,51.5828443222,609.6 -1.1040706317,51.5821436971,609.6 -1.0985980574,51.581791522,609.6 -1.0930963871,51.581791522,609.6 -1.0876238127,51.5821436971,609.6 -1.0822382205,51.5828443222,609.6 -1.0769965823,51.5838859862,609.6 -1.0719543573,51.58525767,609.6 -1.0671649077,51.5869448622,609.6 -1.0626789373,51.5889297119,609.6 -1.0585439565,51.5911912162,609.6 -1.0548037807,51.5937054416,609.6 -1.0514980662,51.596445776,609.6 -1.0486618898,51.5993832088,609.6 -1.0463253752,51.6024866374,609.6 -1.0445133716,51.6057231948,609.6 -1.0432451862,51.6090585972,609.6 -1.0425343761,51.6124575061,609.6 -1.0423885991,51.6158839024,609.6 -1.0428095278,51.6193014675,609.6 -1.0437928263,51.6226739684,609.6 -1.0453281907,51.6259656419,609.6 -1.0473994536,51.6291415743,609.6 -1.0499847507,51.6321680726,609.6 -1.0530567485,51.6350130224,609.6 -1.0565829315,51.6376462301,609.6 -1.0605259443,51.6400397443,609.6 -1.064843987,51.6421681537,609.6 -1.069491258,51.6440088582,609.6 -1.0744184411,51.6455423103,609.6 -1.0795732304,51.6467522233,609.6 -1.084900888,51.6476257459,609.6 -1.0903448282,51.648153599,609.6 -1.0958472222,51.6483301753,609.6 + + + + + + EGRU118B BENSON RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="8160" txt_name="BENSON RWY 01"><tr><td>513342N 0010601W -<br/>513347N 0010653W -<br/>513459N 0010637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to<br/>513454N 0010545W -<br/>513342N 0010601W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1003111111,51.5617916667,609.6 -1.0959105556,51.5817474444,609.6 -1.100727273,51.5818864152,609.6 -1.1055043408,51.5822951597,609.6 -1.1102029444,51.5829703333,609.6 -1.1145972222,51.5630138889,609.6 -1.1003111111,51.5617916667,609.6 + + + + + + EGRU118C BENSON RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="7916" txt_name="BENSON RWY 19"><tr><td>514006N 0010529W -<br/>514001N 0010437W -<br/>513850N 0010453W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to<br/>513854N 0010545W -<br/>514006N 0010529W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0913722222,51.6682888889,609.6 -1.09578375,51.6483301389,609.6 -1.0909598326,51.6481909345,609.6 -1.0861758008,51.6477815696,609.6 -1.0814706944,51.6471053889,609.6 -1.0770527778,51.6670638889,609.6 -1.0913722222,51.6682888889,609.6 + + + + + + EGRU119A CHALGROVE + <table border="1" cellpadding="1" cellspacing="0" row_id="7577" txt_name="CHALGROVE"><tr><td>A circle, 2 NM radius, centred at 514028N 0010507W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.08525,51.7078020585,609.6 -1.0907596062,51.7076254837,609.6 -1.0962106817,51.7070976351,609.6 -1.1015453216,51.7062241201,609.6 -1.1067068659,51.7050142177,609.6 -1.1116405047,51.7034807791,609.6 -1.1162938635,51.7016400909,609.6 -1.1206175612,51.6995117006,609.6 -1.1245657363,51.6971182081,609.6 -1.1280965342,51.6944850246,609.6 -1.1311725506,51.6916401013,609.6 -1.1337612274,51.6886136316,609.6 -1.1358351958,51.6854377297,609.6 -1.1373725631,51.6821460883,609.6 -1.1383571408,51.6787736208,609.6 -1.1387786121,51.6753560901,609.6 -1.1386326357,51.6719297288,609.6 -1.1379208867,51.6685308552,609.6 -1.1366510334,51.665195488,609.6 -1.1348366508,51.6619589652,609.6 -1.1324970718,51.6588555703,609.6 -1.1296571783,51.6559181698,609.6 -1.1263471336,51.6531778659,609.6 -1.1226020606,51.6506636687,609.6 -1.1184616675,51.6484021901,609.6 -1.113969827,51.6464173632,609.6 -1.1091741116,51.6447301904,609.6 -1.1041252912,51.6433585225,609.6 -1.0988767978,51.6423168707,609.6 -1.0934841627,51.6416162538,609.6 -1.0880044322,51.6412640828,609.6 -1.0824955678,51.6412640828,609.6 -1.0770158373,51.6416162538,609.6 -1.0716232022,51.6423168707,609.6 -1.0663747088,51.6433585225,609.6 -1.0613258884,51.6447301904,609.6 -1.056530173,51.6464173632,609.6 -1.0520383325,51.6484021901,609.6 -1.0478979394,51.6506636687,609.6 -1.0441528664,51.6531778659,609.6 -1.0408428217,51.6559181698,609.6 -1.0380029282,51.6588555703,609.6 -1.0356633492,51.6619589652,609.6 -1.0338489666,51.665195488,609.6 -1.0325791133,51.6685308552,609.6 -1.0318673643,51.6719297288,609.6 -1.0317213879,51.6753560901,609.6 -1.0321428592,51.6787736208,609.6 -1.0331274369,51.6821460883,609.6 -1.0346648042,51.6854377297,609.6 -1.0367387726,51.6886136316,609.6 -1.0393274494,51.6916401013,609.6 -1.0424034658,51.6944850246,609.6 -1.0459342637,51.6971182081,609.6 -1.0498824388,51.6995117006,609.6 -1.0542061365,51.7016400909,609.6 -1.0588594953,51.7034807791,609.6 -1.0637931341,51.7050142177,609.6 -1.0689546784,51.7062241201,609.6 -1.0742893183,51.7070976351,609.6 -1.0797403938,51.7076254837,609.6 -1.08525,51.7078020585,609.6 + + + + + + EGRU120A ODIHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7927" txt_name="ODIHAM"><tr><td>A circle, 2 NM radius, centred at 511403N 0005634W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9428083333,51.2674851282,609.6 -0.948265126,51.2673085421,609.6 -0.9536639509,51.2667806596,609.6 -0.9589474603,51.2659070883,609.6 -0.9640595388,51.2646971075,609.6 -0.9689459033,51.2631635688,609.6 -0.9735546824,51.2613227593,609.6 -0.9778369688,51.2591942274,609.6 -0.9817473409,51.2568005738,609.6 -0.9852443446,51.2541672107,609.6 -0.9882909335,51.2513220907,609.6 -0.9908548602,51.2482954088,609.6 -0.9929090163,51.2451192806,609.6 -0.9944317169,51.2418274011,609.6 -0.9954069263,51.2384546858,609.6 -0.995824424,51.2350369,609.6 -0.9956799076,51.2316102789,609.6 -0.9949750335,51.2282111435,609.6 -0.9937173942,51.2248755156,609.6 -0.9919204321,51.2216387361,609.6 -0.9896032933,51.2185350918,609.6 -0.9867906194,51.215597452,609.6 -0.9835122839,51.2128569223,609.6 -0.9798030725,51.2103425156,609.6 -0.9757023133,51.2080808467,609.6 -0.971253459,51.2060958514,609.6 -0.9665036277,51.2044085344,609.6 -0.9615031045,51.2030367485,609.6 -0.9563048117,51.2019950066,609.6 -0.9509637509,51.2012943289,609.6 -0.9455364246,51.2009421274,609.6 -0.9400802421,51.2009421274,609.6 -0.9346529158,51.2012943289,609.6 -0.929311855,51.2019950066,609.6 -0.9241135621,51.2030367485,609.6 -0.919113039,51.2044085344,609.6 -0.9143632076,51.2060958514,609.6 -0.9099143534,51.2080808467,609.6 -0.9058135942,51.2103425156,609.6 -0.9021043828,51.2128569223,609.6 -0.8988260473,51.215597452,609.6 -0.8960133734,51.2185350918,609.6 -0.8936962345,51.2216387361,609.6 -0.8918992725,51.2248755156,609.6 -0.8906416331,51.2282111435,609.6 -0.8899367591,51.2316102789,609.6 -0.8897922427,51.2350369,609.6 -0.8902097403,51.2384546858,609.6 -0.8911849498,51.2418274011,609.6 -0.8927076503,51.2451192806,609.6 -0.8947618065,51.2482954088,609.6 -0.8973257332,51.2513220907,609.6 -0.9003723221,51.2541672107,609.6 -0.9038693258,51.2568005738,609.6 -0.9077796979,51.2591942274,609.6 -0.9120619843,51.2613227593,609.6 -0.9166707633,51.2631635688,609.6 -0.9215571279,51.2646971075,609.6 -0.9266692064,51.2659070883,609.6 -0.9319527157,51.2667806596,609.6 -0.9373515407,51.2673085421,609.6 -0.9428083333,51.2674851282,609.6 + + + + + + EGRU120B ODIHAM RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7744" txt_name="ODIHAM RWY 09"><tr><td>511356N 0010140W -<br/>511428N 0010137W -<br/>511425N 0005942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to<br/>511352N 0005944W -<br/>511356N 0010140W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0277194444,51.2320944444,609.6 -0.9956238056,51.2311932778,609.6 -0.9958410278,51.2341948201,609.6 -0.9956263241,51.2371964328,609.6 -0.9949813611,51.2401736667,609.6 -1.0270638889,51.241075,609.6 -1.0277194444,51.2320944444,609.6 + + + + + + EGRU120C ODIHAM RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7962" txt_name="ODIHAM RWY 27"><tr><td>511410N 0005128W -<br/>511338N 0005130W -<br/>511341N 0005326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to<br/>511414N 0005324W -<br/>511410N 0005128W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8577777778,51.2362194444,609.6 -0.8899854444,51.2371621944,609.6 -0.889775671,51.2341610401,609.6 -0.8899976551,51.2311602307,609.6 -0.8906495,51.2281841944,609.6 -0.8584305556,51.2272416667,609.6 -0.8577777778,51.2362194444,609.6 + + + + + + EGRU121A BLACKBUSHE + <table border="1" cellpadding="1" cellspacing="0" row_id="8052" txt_name="BLACKBUSHE"><tr><td>511738N 0005215W thence clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to<br/>511806N 0004829W -<br/>511801N 0004919W -<br/>511758N 0004954W -<br/>511753N 0005038W -<br/>511746N 0005120W -<br/>511738N 0005215W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.87075,51.2939527778,609.6 -0.8556861111,51.2962277778,609.6 -0.8438138889,51.29795,609.6 -0.8316222222,51.2993666667,609.6 -0.8219555556,51.3003611111,609.6 -0.8080277778,51.3015972222,609.6 -0.8046211679,51.3042314235,609.6 -0.8016523744,51.3070659151,609.6 -0.7991585751,51.3100749158,609.6 -0.7971657046,51.3132272484,609.6 -0.7956945204,51.3164902437,609.6 -0.7947603842,51.319830079,609.6 -0.7943730988,51.3232121275,609.6 -0.7945368009,51.3266013175,609.6 -0.7952499138,51.3299624951,609.6 -0.7965051585,51.3332607896,609.6 -0.7982896245,51.3364619755,609.6 -0.8005848991,51.3395328276,609.6 -0.8033672544,51.3424414674,609.6 -0.8066078902,51.3451576942,609.6 -0.8102732304,51.3476533001,609.6 -0.8143252696,51.349902364,609.6 -0.8187219672,51.3518815221,609.6 -0.8234176835,51.3535702113,609.6 -0.8283636551,51.3549508846,609.6 -0.833508503,51.3560091942,609.6 -0.838798769,51.3567341412,609.6 -0.8441794738,51.3571181909,609.6 -0.8495946925,51.3571573517,609.6 -0.8549881386,51.3568512164,609.6 -0.860303754,51.3562029671,609.6 -0.8654862942,51.3552193412,609.6 -0.8704819069,51.3539105616,609.6 -0.875238694,51.3522902294,609.6 -0.879707254,51.3503751817,609.6 -0.8838411967,51.3481853158,609.6 -0.8875976263,51.3457433816,609.6 -0.8909375871,51.3430747435,609.6 -0.8938264674,51.3402071163,609.6 -0.8962343572,51.337170276,609.6 -0.8981363562,51.3339957498,609.6 -0.8995128292,51.3307164872,609.6 -0.9003496056,51.3273665183,609.6 -0.9006381222,51.3239805991,609.6 -0.9003755074,51.3205938511,609.6 -0.8995646057,51.3172413967,609.6 -0.8982139433,51.3139579952,609.6 -0.8963376347,51.3107776825,609.6 -0.8939552325,51.307733419,609.6 -0.8910915201,51.3048567489,609.6 -0.887776252,51.3021774742,609.6 -0.8840438431,51.2997233468,609.6 -0.8799330102,51.2975197822,609.6 -0.8754863704,51.2955895979,609.6 -0.87075,51.2939527778,609.6 + + + + + + EGRU121B BLACKBUSHE RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7843" txt_name="BLACKBUSHE RWY 07"><tr><td>511815N 0005513W -<br/>511845N 0005530W -<br/>511904N 0005359W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to<br/>511834N 0005343W -<br/>511815N 0005513W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9204,51.3040638889,609.6 -0.8952721667,51.3093216389,609.6 -0.8971743106,51.3120790247,609.6 -0.8986723185,51.3149326267,609.6 -0.8997539444,51.3178592222,609.6 -0.9249277778,51.3125916667,609.6 -0.9204,51.3040638889,609.6 + + + + + + EGRU121C BLACKBUSHE RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8021" txt_name="BLACKBUSHE RWY 25"><tr><td>512038N 0004631W -<br/>512007N 0004614W -<br/>511949N 0004743W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to<br/>512019N 0004800W -<br/>512038N 0004631W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7751972222,51.343825,609.6 -0.7998953611,51.3386891667,609.6 -0.7979607589,51.3359402315,609.6 -0.7964298273,51.3330932315,609.6 -0.7953149722,51.3301713611,609.6 -0.7706638889,51.3352972222,609.6 -0.7751972222,51.343825,609.6 + + + + + + EGRU122A WYCOMBE AIR PARK/BOOKER + <table border="1" cellpadding="1" cellspacing="0" row_id="8121" txt_name="WYCOMBE AIR PARK/BOOKER"><tr><td>A circle, 2 NM radius, centred at 513642N 0004830W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8082305556,51.6450218609,609.6 -0.8137325491,51.6448452845,609.6 -0.8191760931,51.6443174311,609.6 -0.824503363,51.6434439081,609.6 -0.8296577772,51.6422339944,609.6 -0.8345846019,51.6407005416,609.6 -0.8392315348,51.6388598362,609.6 -0.8435492635,51.6367314258,609.6 -0.8474919896,51.6343379104,609.6 -0.8510179164,51.6317047013,609.6 -0.8540896911,51.62885975,609.6 -0.8566748005,51.6258332502,609.6 -0.8587459132,51.622657316,609.6 -0.8602811664,51.6193656408,609.6 -0.8612643938,51.615993138,609.6 -0.8616852924,51.612575571,609.6 -0.8615395265,51.6091491728,609.6 -0.8608287685,51.6057502619,609.6 -0.8595606757,51.6024148575,609.6 -0.8577488042,51.5991782982,609.6 -0.8554124598,51.5960748678,609.6 -0.8525764898,51.5931374331,609.6 -0.8492710157,51.590397097,609.6 -0.8455311118,51.58788287,609.6 -0.8413964315,51.5856213643,609.6 -0.8369107871,51.5836365134,609.6 -0.8321216854,51.5819493201,609.6 -0.8270798266,51.5805776354,609.6 -0.8218385692,51.5795359707,609.6 -0.816453368,51.5788353451,609.6 -0.810981191,51.5784831698,609.6 -0.8054799201,51.5784831698,609.6 -0.8000077431,51.5788353451,609.6 -0.794622542,51.5795359707,609.6 -0.7893812845,51.5805776354,609.6 -0.7843394257,51.5819493201,609.6 -0.779550324,51.5836365134,609.6 -0.7750646796,51.5856213643,609.6 -0.7709299993,51.58788287,609.6 -0.7671900954,51.590397097,609.6 -0.7638846213,51.5931374331,609.6 -0.7610486513,51.5960748678,609.6 -0.7587123069,51.5991782982,609.6 -0.7569004354,51.6024148575,609.6 -0.7556323426,51.6057502619,609.6 -0.7549215847,51.6091491728,609.6 -0.7547758187,51.612575571,609.6 -0.7551967173,51.615993138,609.6 -0.7561799447,51.6193656408,609.6 -0.757715198,51.622657316,609.6 -0.7597863106,51.6258332502,609.6 -0.76237142,51.62885975,609.6 -0.7654431947,51.6317047013,609.6 -0.7689691215,51.6343379104,609.6 -0.7729118476,51.6367314258,609.6 -0.7772295763,51.6388598362,609.6 -0.7818765093,51.6407005416,609.6 -0.7868033339,51.6422339944,609.6 -0.7919577481,51.6434439081,609.6 -0.797285018,51.6443174311,609.6 -0.802728562,51.6448452845,609.6 -0.8082305556,51.6450218609,609.6 + + + + + + EGRU122B WYCOMBE AIR PARK/BOOKER RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7854" txt_name="WYCOMBE AIR PARK/BOOKER RWY 06"><tr><td>513508N 0005225W -<br/>513536N 0005249W -<br/>513602N 0005131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to<br/>513533N 0005107W -<br/>513508N 0005225W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8734888889,51.5854194444,609.6 -0.8518406944,51.5924746389,609.6 -0.8544514271,51.5950007053,609.6 -0.8566861956,51.597663026,609.6 -0.85852675,51.6004399444,609.6 -0.8801694444,51.5933861111,609.6 -0.8734888889,51.5854194444,609.6 + + + + + + EGRU122C WYCOMBE AIR PARK/BOOKER RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7798" txt_name="WYCOMBE AIR PARK/BOOKER RWY 24"><tr><td>513817N 0004434W -<br/>513748N 0004410W -<br/>513723N 0004529W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to<br/>513752N 0004553W -<br/>513817N 0004434W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7428694444,51.6380305556,609.6 -0.7645970833,51.6309821389,609.6 -0.7619873992,51.6284546928,609.6 -0.7597547123,51.6257910769,609.6 -0.7579171667,51.623013,609.6 -0.7361805556,51.6300638889,609.6 -0.7428694444,51.6380305556,609.6 + + + + + + EGRU122D WYCOMBE AIR PARK/BOOKER RWY 06G + <table border="1" cellpadding="1" cellspacing="0" row_id="7690" txt_name="WYCOMBE AIR PARK/BOOKER RWY 06G"><tr><td>513506N 0005218W -<br/>513535N 0005242W -<br/>513559N 0005129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to<br/>513531N 0005104W -<br/>513506N 0005218W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8717527778,51.5851333333,609.6 -0.8511163333,51.591854,609.6 -0.8538205929,51.5943427601,609.6 -0.8561537856,51.5969732224,609.6 -0.8580968611,51.5997239722,609.6 -0.8784277778,51.5931027778,609.6 -0.8717527778,51.5851333333,609.6 + + + + + + EGRU122E WYCOMBE AIR PARK/BOOKER RWY 24G + <table border="1" cellpadding="1" cellspacing="0" row_id="8072" txt_name="WYCOMBE AIR PARK/BOOKER RWY 24G"><tr><td>513814N 0004433W -<br/>513746N 0004408W -<br/>513720N 0004527W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to<br/>513749N 0004550W -<br/>513814N 0004433W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7423638889,51.6373111111,609.6 -0.7638803889,51.6303364444,609.6 -0.7613668981,51.627771051,609.6 -0.7592355649,51.6250750191,609.6 -0.7575036944,51.6222703333,609.6 -0.7356805556,51.6293444444,609.6 -0.7423638889,51.6373111111,609.6 + + + + + + EGRU122G WYCOMBE AIR PARK/BOOKER RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7796" txt_name="WYCOMBE AIR PARK/BOOKER RWY 35"><tr><td>513351N 0004703W -<br/>513344N 0004754W -<br/>513443N 0004815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to<br/>513450N 0004724W -<br/>513351N 0004703W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7843015278,51.5641660833,609.6 -0.7899565833,51.5804449444,609.6 -0.7945577486,51.5795466346,609.6 -0.7992699984,51.5789101889,609.6 -0.8040550556,51.5785408056,609.6 -0.798395,51.562262,609.6 -0.7843015278,51.5641660833,609.6 + + + + + + EGRU123A FARNBOROUGH + <table border="1" cellpadding="1" cellspacing="0" row_id="7702" txt_name="FARNBOROUGH"><tr><td>511758N 0004954W -<br/>511801N 0004919W -<br/>511806N 0004829W -<br/>511812N 0004723W -<br/>511817N 0004705W -<br/>511851N 0004551W -<br/>511856N 0004537W thence clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to -<br/>511758N 0004954W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8316222222,51.2993666667,609.6 -0.8349233581,51.2961419297,609.6 -0.8377383331,51.2927409314,609.6 -0.8400421019,51.2891919749,609.6 -0.8418152365,51.2855251742,609.6 -0.8430428226,51.2817716363,609.6 -0.843714583,51.2779631961,609.6 -0.8438249598,51.2741321464,609.6 -0.8433731571,51.2703109638,609.6 -0.842363143,51.2665320331,609.6 -0.8408036111,51.2628273734,609.6 -0.8387079028,51.2592283667,609.6 -0.8360938895,51.2557654929,609.6 -0.8329838181,51.2524680725,609.6 -0.829404119,51.2493640189,609.6 -0.8253851801,51.2464796031,609.6 -0.8209610875,51.2438392327,609.6 -0.8161693361,51.2414652461,609.6 -0.8110505121,51.2393777248,609.6 -0.8056479499,51.2375943248,609.6 -0.8000073667,51.2361301276,609.6 -0.7941764778,51.2349975143,609.6 -0.7882045952,51.2342060613,609.6 -0.7821422136,51.23376246,609.6 -0.776040587,51.2336704608,609.6 -0.7699512981,51.2339308414,609.6 -0.7639258263,51.2345414005,609.6 -0.758015116,51.2354969763,609.6 -0.7522691488,51.2367894894,609.6 -0.7467365243,51.238408011,609.6 -0.7414640515,51.2403388547,609.6 -0.7364963554,51.2425656908,609.6 -0.7318755007,51.2450696839,609.6 -0.7276406369,51.2478296513,609.6 -0.7238276671,51.2508222408,609.6 -0.7204689437,51.2540221271,609.6 -0.7175929929,51.2574022255,609.6 -0.7152242709,51.2609339197,609.6 -0.7133829545,51.2645873035,609.6 -0.7120847664,51.2683314329,609.6 -0.7113408381,51.2721345878,609.6 -0.7111576111,51.2759645403,609.6 -0.7115367784,51.2797888272,609.6 -0.7124752644,51.2835750257,609.6 -0.7139652472,51.2872910278,609.6 -0.7159942199,51.290905313,609.6 -0.7185450924,51.2943872168,609.6 -0.7215963329,51.2977071907,609.6 -0.725122147,51.3008370544,609.6 -0.729092694,51.3037502357,609.6 -0.7334743386,51.3064219971,609.6 -0.7382299347,51.3088296472,609.6 -0.7433191407,51.3109527342,609.6 -0.7486987626,51.3127732211,609.6 -0.7543231217,51.3142756395,609.6 -0.7601444444,51.3154472222,609.6 -0.7641027778,51.3140444444,609.6 -0.7846027778,51.3046388889,609.6 -0.7897027778,51.3033833333,609.6 -0.8080277778,51.3015972222,609.6 -0.8219555556,51.3003611111,609.6 -0.8316222222,51.2993666667,609.6 + + + + + + EGRU123B FARNBOROUGH RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8088" txt_name="FARNBOROUGH RWY 06"><tr><td>511452N 0005042W -<br/>511521N 0005107W -<br/>511536N 0005021W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to<br/>511507N 0004957W -<br/>511452N 0005042W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8450972222,51.2477583333,609.6 -0.8324629167,51.2519783056,609.6 -0.8349976079,51.2545235792,609.6 -0.8372336199,51.2571768339,609.6 -0.8391593056,51.2599242778,609.6 -0.8518138889,51.2556972222,609.6 -0.8450972222,51.2477583333,609.6 + + + + + + EGRU123C FARNBOROUGH RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7832" txt_name="FARNBOROUGH RWY 24"><tr><td>511811N 0004233W -<br/>511743N 0004209W -<br/>511727N 0004257W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to<br/>511755N 0004322W -<br/>511811N 0004233W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.709275,51.3031861111,609.6 -0.7226773611,51.2987325,609.6 -0.7201248589,51.2961928717,609.6 -0.717871246,51.2935444601,609.6 -0.7159282222,51.2908010556,609.6 -0.7025472222,51.2952472222,609.6 -0.709275,51.3031861111,609.6 + + + + + + EGRU124A WHITE WALTHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7650" txt_name="WHITE WALTHAM"><tr><td>A circle, 2 NM radius, centred at 513002N 0004629W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7748333333,51.5339502723,609.6 -0.7803219262,51.5337736931,609.6 -0.7857522123,51.5332458312,609.6 -0.7910665085,51.532372294,609.6 -0.7962083715,51.5311623606,609.6 -0.801123201,51.5296288826,609.6 -0.8057588225,51.5277881466,609.6 -0.8100660436,51.5256597005,609.6 -0.8139991778,51.5232661445,609.6 -0.8175165298,51.5206328903,609.6 -0.8205808377,51.5177878894,609.6 -0.8231596671,51.5147613361,609.6 -0.8252257528,51.5115853449,609.6 -0.8267572846,51.5082936097,609.6 -0.827738135,51.5049210445,609.6 -0.8281580254,51.5015034131,609.6 -0.8280126299,51.4980769494,609.6 -0.8273036164,51.4946779725,609.6 -0.8260386228,51.4913425024,609.6 -0.8242311716,51.4881058784,609.6 -0.821900521,51.4850023851,609.6 -0.8190714576,51.4820648901,609.6 -0.8157740293,51.4793244971,609.6 -0.8120432247,51.4768102173,609.6 -0.807918601,51.4745486636,609.6 -0.8034438637,51.4725637701,609.6 -0.7986664044,51.4708765405,609.6 -0.7936368003,51.469504826,609.6 -0.7884082804,51.4684631386,609.6 -0.7830361654,51.4677624977,609.6 -0.7775772851,51.4674103147,609.6 -0.7720893815,51.4674103147,609.6 -0.7666305013,51.4677624977,609.6 -0.7612583863,51.4684631386,609.6 -0.7560298664,51.469504826,609.6 -0.7510002623,51.4708765405,609.6 -0.746222803,51.4725637701,609.6 -0.7417480657,51.4745486636,609.6 -0.7376234419,51.4768102173,609.6 -0.7338926374,51.4793244971,609.6 -0.7305952091,51.4820648901,609.6 -0.7277661456,51.4850023851,609.6 -0.7254354951,51.4881058784,609.6 -0.7236280438,51.4913425024,609.6 -0.7223630502,51.4946779725,609.6 -0.7216540367,51.4980769494,609.6 -0.7215086413,51.5015034131,609.6 -0.7219285317,51.5049210445,609.6 -0.7229093821,51.5082936097,609.6 -0.7244409139,51.5115853449,609.6 -0.7265069995,51.5147613361,609.6 -0.729085829,51.5177878894,609.6 -0.7321501369,51.5206328903,609.6 -0.7356674889,51.5232661445,609.6 -0.7396006231,51.5256597005,609.6 -0.7439078442,51.5277881466,609.6 -0.7485434657,51.5296288826,609.6 -0.7534582952,51.5311623606,609.6 -0.7586001581,51.532372294,609.6 -0.7639144543,51.5332458312,609.6 -0.7693447405,51.5337736931,609.6 -0.7748333333,51.5339502723,609.6 + + + + + + EGRU124B WHITE WALTHAM RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8126" txt_name="WHITE WALTHAM RWY 03"><tr><td>512712N 0004802W -<br/>512727N 0004848W -<br/>512819N 0004807W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>512807N 0004719W -<br/>512712N 0004802W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8004888889,51.4534388889,609.6 -0.7886194722,51.4684981389,609.6 -0.7932141707,51.4694066717,609.6 -0.7976589203,51.4705705112,609.6 -0.8019174444,51.4719801667,609.6 -0.8133944444,51.4574138889,609.6 -0.8004888889,51.4534388889,609.6 + + + + + + EGRU124C WHITE WALTHAM RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7606" txt_name="WHITE WALTHAM RWY 21"><tr><td>513247N 0004436W -<br/>513233N 0004349W -<br/>513137N 0004433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>513154N 0004518W -<br/>513247N 0004436W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7432027778,51.5463361111,609.6 -0.7549029444,51.5315407778,609.6 -0.7505130261,51.5302910944,609.6 -0.746322272,51.5287990749,609.6 -0.7423649722,51.5270769444,609.6 -0.7302722222,51.5423638889,609.6 -0.7432027778,51.5463361111,609.6 + + + + + + EGRU124D WHITE WALTHAM RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="8172" txt_name="WHITE WALTHAM RWY 07"><tr><td>512831N 0005037W -<br/>512900N 0005059W -<br/>512926N 0004932W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>512857N 0004910W -<br/>512831N 0005037W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8435944444,51.4752861111,609.6 -0.8194776389,51.482447,609.6 -0.8219270335,51.4850334633,609.6 -0.8239931833,51.4877472443,609.6 -0.8256592222,51.49056625,609.6 -0.8497666667,51.4834083333,609.6 -0.8435944444,51.4752861111,609.6 + + + + + + EGRU124E WHITE WALTHAM RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7764" txt_name="WHITE WALTHAM RWY 25"><tr><td>513134N 0004222W -<br/>513104N 0004159W -<br/>513039N 0004326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>513108N 0004349W -<br/>513134N 0004222W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7060083333,51.5259861111,609.6 -0.7301535556,51.51885275,609.6 -0.7277079881,51.5162648704,609.6 -0.7256465231,51.5135499515,609.6 -0.7239859167,51.5107301111,609.6 -0.6998305556,51.5178666667,609.6 -0.7060083333,51.5259861111,609.6 + + + + + + EGRU124F WHITE WALTHAM RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7674" txt_name="WHITE WALTHAM RWY 11"><tr><td>513039N 0005100W -<br/>513109N 0005042W -<br/>513052N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>513020N 0004939W -<br/>513039N 0005100W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8499277778,51.5107083333,609.6 -0.8275695,51.5056710833,609.6 -0.8266300624,51.5086235565,609.6 -0.8252669632,51.5115109942,609.6 -0.8234912778,51.5143097778,609.6 -0.8450222222,51.5191611111,609.6 -0.8499277778,51.5107083333,609.6 + + + + + + EGRU124G WHITE WALTHAM RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="8108" txt_name="WHITE WALTHAM RWY 29"><tr><td>512909N 0004152W -<br/>512839N 0004210W -<br/>512900N 0004345W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to<br/>512930N 0004324W -<br/>512909N 0004152W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6978833333,51.4859083333,609.6 -0.7234618056,51.4917057222,609.6 -0.724968234,51.4888470135,609.6 -0.7268817969,51.4860848759,609.6 -0.7291868056,51.4834418611,609.6 -0.7027833333,51.4774583333,609.6 -0.6978833333,51.4859083333,609.6 + + + + + + EGRU125A HALTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7638" txt_name="HALTON"><tr><td>A circle, 2 NM radius, centred at 514732N 0004411W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.73645,51.8255736098,609.6 -0.7419739621,51.825397038,609.6 -0.7474392404,51.8248691985,609.6 -0.7527877787,51.8239956984,609.6 -0.7579627689,51.8227858168,609.6 -0.7629092579,51.8212524049,609.6 -0.7675747343,51.819411749,609.6 -0.7719096885,51.8172833964,609.6 -0.7758681392,51.8148899469,609.6 -0.7794081229,51.8122568112,609.6 -0.7824921382,51.8094119403,609.6 -0.7850875426,51.8063855272,609.6 -0.7871668962,51.8032096856,609.6 -0.78870825,51.7999181077,609.6 -0.7896953741,51.7965457063,609.6 -0.7901179254,51.7931282437,609.6 -0.789971552,51.7897019518,609.6 -0.7892579341,51.786303148,609.6 -0.7879847607,51.7829678504,609.6 -0.7861656427,51.7797313962,609.6 -0.7838199641,51.7766280679,609.6 -0.7809726717,51.7736907313,609.6 -0.7776540078,51.7709504877,609.6 -0.7738991868,51.7684363465,609.6 -0.7697480205,51.7661749187,609.6 -0.7652444955,51.7641901369,609.6 -0.760436308,51.7625030027,609.6 -0.7553743596,51.7611313664,609.6 -0.7501122209,51.7600897386,609.6 -0.744705567,51.7593891379,609.6 -0.7392115921,51.7590369751,609.6 -0.7336884079,51.7590369751,609.6 -0.728194433,51.7593891379,609.6 -0.7227877791,51.7600897386,609.6 -0.7175256404,51.7611313664,609.6 -0.712463692,51.7625030027,609.6 -0.7076555045,51.7641901369,609.6 -0.7031519795,51.7661749187,609.6 -0.6990008132,51.7684363465,609.6 -0.6952459922,51.7709504877,609.6 -0.6919273283,51.7736907313,609.6 -0.6890800359,51.7766280679,609.6 -0.6867343573,51.7797313962,609.6 -0.6849152393,51.7829678504,609.6 -0.6836420659,51.786303148,609.6 -0.682928448,51.7897019518,609.6 -0.6827820746,51.7931282437,609.6 -0.6832046259,51.7965457063,609.6 -0.68419175,51.7999181077,609.6 -0.6857331038,51.8032096856,609.6 -0.6878124574,51.8063855272,609.6 -0.6904078618,51.8094119403,609.6 -0.6934918771,51.8122568112,609.6 -0.6970318608,51.8148899469,609.6 -0.7009903115,51.8172833964,609.6 -0.7053252657,51.819411749,609.6 -0.7099907421,51.8212524049,609.6 -0.7149372311,51.8227858168,609.6 -0.7201122213,51.8239956984,609.6 -0.7254607596,51.8248691985,609.6 -0.7309260379,51.825397038,609.6 -0.73645,51.8255736098,609.6 + + + + + + EGRU125B HALTON RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="7928" txt_name="HALTON RWY 02"><tr><td>514440N 0004521W -<br/>514451N 0004610W -<br/>514546N 0004539W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to<br/>514535N 0004450W -<br/>514440N 0004521W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7558487222,51.7445320556,609.6 -0.7472673333,51.7596761944,609.6 -0.7519601648,51.760413542,609.6 -0.7565269625,51.7614102361,609.6 -0.7609306111,51.7626581667,609.6 -0.7695065,51.7475157222,609.6 -0.7558487222,51.7445320556,609.6 + + + + + + EGRU125C HALTON RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7823" txt_name="HALTON RWY 20"><tr><td>515024N 0004301W -<br/>515013N 0004212W -<br/>514919N 0004243W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to<br/>514930N 0004332W -<br/>515024N 0004301W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7170165,51.8400288889,609.6 -0.7256216944,51.8248898889,609.6 -0.7209224785,51.8241517558,609.6 -0.7163499724,51.8231539352,609.6 -0.7119414722,51.8219045833,609.6 -0.7033307222,51.83704525,609.6 -0.7170165,51.8400288889,609.6 + + + + + + EGRU125D HALTON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7896" txt_name="HALTON RWY 07"><tr><td>514615N 0004829W -<br/>514646N 0004846W -<br/>514705N 0004719W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to<br/>514635N 0004701W -<br/>514615N 0004829W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8080578056,51.7708836389,609.6 -0.78350425,51.7762662222,609.6 -0.7856425451,51.7789628325,609.6 -0.7873803361,51.781768038,609.6 -0.7887033889,51.784659,609.6 -0.8128740833,51.7793601944,609.6 -0.8080578056,51.7708836389,609.6 + + + + + + EGRU125E HALTON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7847" txt_name="HALTON RWY 25"><tr><td>514840N 0004002W -<br/>514810N 0003944W -<br/>514753N 0004101W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to<br/>514824N 0004117W -<br/>514840N 0004002W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6671238889,51.8112181389,609.6 -0.6880245278,51.8066635556,609.6 -0.6861315652,51.803896992,609.6 -0.6846489466,51.8010358551,609.6 -0.6835886944,51.7981034722,609.6 -0.6623042222,51.8027416389,609.6 -0.6671238889,51.8112181389,609.6 + + + + + + EGRU126A FAIROAKS + <table border="1" cellpadding="1" cellspacing="0" row_id="7575" txt_name="FAIROAKS"><tr><td>A circle, 2 NM radius, centred at 512053N 0003331W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5587083333,51.3813205885,609.6 -0.5641786514,51.3811440053,609.6 -0.5695908576,51.3806161316,609.6 -0.5748874614,51.3797425749,609.6 -0.580012208,51.3785326144,609.6 -0.5849106794,51.3769991016,609.6 -0.5895308752,51.3751583236,609.6 -0.593823767,51.3730298284,609.6 -0.5977438204,51.3706362166,609.6 -0.6012494788,51.3680029,609.6 -0.604303604,51.3651578309,609.6 -0.6068738693,51.362131204,609.6 -0.6089330994,51.3589551344,609.6 -0.6104595561,51.3556633166,609.6 -0.6114371648,51.3522906655,609.6 -0.6118556802,51.3488729457,609.6 -0.61171079,51.3454463918,609.6 -0.6110041553,51.3420473242,609.6 -0.6097433881,51.3387117637,609.6 -0.6079419647,51.3354750507,609.6 -0.605619079,51.3323714709,609.6 -0.6027994342,51.329433893,609.6 -0.5995129781,51.3266934217,609.6 -0.5957945826,51.3241790693,609.6 -0.5916836731,51.3219174496,609.6 -0.5872238101,51.3199324978,609.6 -0.5824622279,51.3182452181,609.6 -0.5774493358,51.3168734627,609.6 -0.5722381866,51.3158317441,609.6 -0.5668839175,51.3151310822,609.6 -0.5614431705,51.3147788885,609.6 -0.5559734962,51.3147788885,609.6 -0.5505327491,51.3151310822,609.6 -0.5451784801,51.3158317441,609.6 -0.5399673309,51.3168734627,609.6 -0.5349544388,51.3182452181,609.6 -0.5301928566,51.3199324978,609.6 -0.5257329936,51.3219174496,609.6 -0.5216220841,51.3241790693,609.6 -0.5179036886,51.3266934217,609.6 -0.5146172324,51.329433893,609.6 -0.5117975877,51.3323714709,609.6 -0.5094747019,51.3354750507,609.6 -0.5076732786,51.3387117637,609.6 -0.5064125113,51.3420473242,609.6 -0.5057058767,51.3454463918,609.6 -0.5055609864,51.3488729457,609.6 -0.5059795018,51.3522906655,609.6 -0.5069571105,51.3556633166,609.6 -0.5084835673,51.3589551344,609.6 -0.5105427974,51.362131204,609.6 -0.5131130626,51.3651578309,609.6 -0.5161671879,51.3680029,609.6 -0.5196728463,51.3706362166,609.6 -0.5235928997,51.3730298284,609.6 -0.5278857915,51.3751583236,609.6 -0.5325059873,51.3769991016,609.6 -0.5374044587,51.3785326144,609.6 -0.5425292053,51.3797425749,609.6 -0.5478258091,51.3806161316,609.6 -0.5532380153,51.3811440053,609.6 -0.5587083333,51.3813205885,609.6 + + + + + + EGRU126B FAIROAKS RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8068" txt_name="FAIROAKS RWY 06"><tr><td>511907N 0003712W -<br/>511934N 0003739W -<br/>512003N 0003626W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to<br/>511936N 0003558W -<br/>511907N 0003712W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6199333333,51.318625,609.6 -0.5994920556,51.3266777222,609.6 -0.6023993034,51.3290671078,609.6 -0.6049511893,51.3316109024,609.6 -0.6071268889,51.3342884167,609.6 -0.6275583333,51.3262388889,609.6 -0.6199333333,51.318625,609.6 + + + + + + EGRU126C FAIROAKS RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="8118" txt_name="FAIROAKS RWY 24"><tr><td>512239N 0002949W -<br/>512212N 0002922W -<br/>512142N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to<br/>512210N 0003104W -<br/>512239N 0002949W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4969416667,51.3775888889,609.6 -0.5178943056,51.3693692222,609.6 -0.5149878589,51.3669779903,609.6 -0.5124379479,51.3644324142,609.6 -0.5102653056,51.36175325,609.6 -0.4893055556,51.369975,609.6 -0.4969416667,51.3775888889,609.6 + + + + + + EGRU127A DENHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7590" txt_name="DENHAM"><tr><td>A circle, 2 NM radius, centred at 513518N 0003047W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5129944444,51.6217164382,609.6 -0.5184936191,51.6215398612,609.6 -0.5239343742,51.621012006,609.6 -0.5292589149,51.6201384801,609.6 -0.5344106889,51.6189285623,609.6 -0.5393349903,51.6173951042,609.6 -0.5439795438,51.6155543924,609.6 -0.5482950621,51.6134259744,609.6 -0.5522357706,51.6110324506,609.6 -0.5557598936,51.608399232,609.6 -0.5588300976,51.6055542703,609.6 -0.5614138859,51.6025277593,609.6 -0.5634839411,51.5993518132,609.6 -0.5650184115,51.5960601253,609.6 -0.5660011389,51.5926876095,609.6 -0.5664218254,51.589270029,609.6 -0.5662761375,51.585843617,609.6 -0.5655657464,51.5824446922,609.6 -0.5642983057,51.5791092741,609.6 -0.5624873639,51.5758727012,609.6 -0.5601522173,51.5727692576,609.6 -0.5573177001,51.5698318103,609.6 -0.5540139185,51.5670914623,609.6 -0.5502759287,51.5645772242,609.6 -0.5461433639,51.5623157084,609.6 -0.5416600139,51.5603308485,609.6 -0.5368733613,51.5586436476,609.6 -0.5318340803,51.5572719567,609.6 -0.5265955023,51.5562302872,609.6 -0.5212130539,51.5555296584,609.6 -0.5157436739,51.5551774815,609.6 -0.510245215,51.5551774815,609.6 -0.504775835,51.5555296584,609.6 -0.4993933866,51.5562302872,609.6 -0.4941548086,51.5572719567,609.6 -0.4891155276,51.5586436476,609.6 -0.484328875,51.5603308485,609.6 -0.4798455249,51.5623157084,609.6 -0.4757129602,51.5645772242,609.6 -0.4719749703,51.5670914623,609.6 -0.4686711888,51.5698318103,609.6 -0.4658366716,51.5727692576,609.6 -0.4635015249,51.5758727012,609.6 -0.4616905832,51.5791092741,609.6 -0.4604231424,51.5824446922,609.6 -0.4597127514,51.585843617,609.6 -0.4595670635,51.589270029,609.6 -0.4599877499,51.5926876095,609.6 -0.4609704774,51.5960601253,609.6 -0.4625049477,51.5993518132,609.6 -0.464575003,51.6025277593,609.6 -0.4671587913,51.6055542703,609.6 -0.4702289953,51.608399232,609.6 -0.4737531183,51.6110324506,609.6 -0.4776938267,51.6134259744,609.6 -0.4820093451,51.6155543924,609.6 -0.4866538986,51.6173951042,609.6 -0.4915782,51.6189285623,609.6 -0.4967299739,51.6201384801,609.6 -0.5020545147,51.621012006,609.6 -0.5074952698,51.6215398612,609.6 -0.5129944444,51.6217164382,609.6 + + + + + + EGRU127B DENHAM RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7659" txt_name="DENHAM RWY 06"><tr><td>513336N 0003432W -<br/>513404N 0003459W -<br/>513431N 0003344W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to<br/>513404N 0003317W -<br/>513336N 0003432W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5756055556,51.5599277778,609.6 -0.5547771667,51.56767425,609.6 -0.5576101111,51.5701051677,609.6 -0.5600801312,51.5726852958,609.6 -0.5621670833,51.5753936389,609.6 -0.5829861111,51.56765,609.6 -0.5756055556,51.5599277778,609.6 + + + + + + EGRU127C DENHAM RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7990" txt_name="DENHAM RWY 24"><tr><td>513700N 0002704W -<br/>513632N 0002637W -<br/>513605N 0002750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to<br/>513633N 0002816W -<br/>513700N 0002704W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.450975,51.6166444444,609.6 -0.4711767778,51.60916325,609.6 -0.4683454519,51.6067302115,609.6 -0.4658782366,51.6041480831,609.6 -0.4637951944,51.6014379167,609.6 -0.4435833333,51.6089222222,609.6 -0.450975,51.6166444444,609.6 + + + + + + EGRU127D DENHAM RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="7708" txt_name="DENHAM RWY 12"><tr><td>513623N 0003455W -<br/>513652N 0003431W -<br/>513629N 0003322W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to<br/>513600N 0003347W -<br/>513623N 0003455W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5820527778,51.6064472222,609.6 -0.5630313056,51.6001324167,609.6 -0.5611342148,51.6028946338,609.6 -0.5588447291,51.6055390603,609.6 -0.5561814444,51.6080441389,609.6 -0.57525,51.614375,609.6 -0.5820527778,51.6064472222,609.6 + + + + + + EGRU127E DENHAM RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="7940" txt_name="DENHAM RWY 30"><tr><td>513416N 0002641W -<br/>513347N 0002706W -<br/>513409N 0002810W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to<br/>513437N 0002746W -<br/>513416N 0002641W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4448222222,51.570975,609.6 -0.4628163333,51.5769761389,609.6 -0.464678404,51.5742051095,609.6 -0.4669335187,51.5715499091,609.6 -0.4695632778,51.5690321389,609.6 -0.4516166667,51.5630472222,609.6 -0.4448222222,51.570975,609.6 + + + + + + EGRU128A LONDON HEATHROW + <table border="1" cellpadding="1" cellspacing="0" row_id="7809" txt_name="LONDON HEATHROW"><tr><td>A circle, 2.5 NM radius, centred at 512839N 0002741W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.46135,51.519198392,609.6 -0.4675046258,51.5190207088,609.6 -0.4736065998,51.5184891791,609.6 -0.4796037246,51.5176083498,609.6 -0.4854447066,51.5163857558,609.6 -0.4910795983,51.5148318544,609.6 -0.4964602286,51.5129599359,609.6 -0.5015406165,51.5107860084,609.6 -0.5062773666,51.5083286606,609.6 -0.5106300405,51.5056089011,609.6 -0.5145615031,51.5026499783,609.6 -0.5180382389,51.4994771803,609.6 -0.5210306378,51.4961176176,609.6 -0.5235132452,51.4925999902,609.6 -0.525464977,51.4889543421,609.6 -0.526869296,51.4852118033,609.6 -0.5277143491,51.4814043233,609.6 -0.5279930642,51.4775643984,609.6 -0.5277032056,51.4737247933,609.6 -0.5268473884,51.4699182621,609.6 -0.5254330514,51.4661772686,609.6 -0.5234723888,51.4625337097,609.6 -0.5209822419,51.4590186443,609.6 -0.5179839515,51.4556620291,609.6 -0.5145031729,51.4524924637,609.6 -0.510569654,51.4495369488,609.6 -0.5062169801,51.4468206561,609.6 -0.5014822864,51.4443667159,609.6 -0.4964059411,51.4421960211,609.6 -0.4910312023,51.4403270501,609.6 -0.4854038501,51.4387757108,609.6 -0.479571799,51.4375552059,609.6 -0.4735846922,51.436675922,609.6 -0.4674934822,51.436145341,609.6 -0.46135,51.4359679776,609.6 -0.4552065178,51.436145341,609.6 -0.4491153078,51.436675922,609.6 -0.443128201,51.4375552059,609.6 -0.4372961499,51.4387757108,609.6 -0.4316687977,51.4403270501,609.6 -0.4262940589,51.4421960211,609.6 -0.4212177136,51.4443667159,609.6 -0.4164830199,51.4468206561,609.6 -0.412130346,51.4495369488,609.6 -0.4081968271,51.4524924637,609.6 -0.4047160485,51.4556620291,609.6 -0.4017177581,51.4590186443,609.6 -0.3992276112,51.4625337097,609.6 -0.3972669486,51.4661772686,609.6 -0.3958526116,51.4699182621,609.6 -0.3949967944,51.4737247933,609.6 -0.3947069358,51.4775643984,609.6 -0.3949856509,51.4814043233,609.6 -0.395830704,51.4852118033,609.6 -0.397235023,51.4889543421,609.6 -0.3991867548,51.4925999902,609.6 -0.4016693622,51.4961176176,609.6 -0.4046617611,51.4994771803,609.6 -0.4081384969,51.5026499783,609.6 -0.4120699595,51.5056089011,609.6 -0.4164226334,51.5083286606,609.6 -0.4211593835,51.5107860084,609.6 -0.4262397714,51.5129599359,609.6 -0.4316204017,51.5148318544,609.6 -0.4372552934,51.5163857558,609.6 -0.4430962754,51.5176083498,609.6 -0.4490934002,51.5184891791,609.6 -0.4551953742,51.5190207088,609.6 -0.46135,51.519198392,609.6 + + + + + + EGRU128B LONDON HEATHROW RWY 09L + <table border="1" cellpadding="1" cellspacing="0" row_id="8029" txt_name="LONDON HEATHROW RWY 09L"><tr><td>512814N 0003325W -<br/>512902N 0003325W -<br/>512903N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to<br/>512814N 0003137W -<br/>512814N 0003325W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5569003333,51.4704933333,609.6 -0.5270472778,51.4706154722,609.6 -0.5277391047,51.473972328,609.6 -0.5279918993,51.4773531895,609.6 -0.527803899,51.4807356961,609.6 -0.52717625,51.4840974722,609.6 -0.5570173333,51.4839753889,609.6 -0.5569003333,51.4704933333,609.6 + + + + + + EGRU128C LONDON HEATHROW RWY 27R + <table border="1" cellpadding="1" cellspacing="0" row_id="7511" txt_name="LONDON HEATHROW RWY 27R"><tr><td>512905N 0002141W -<br/>512816N 0002141W -<br/>512816N 0002344W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to<br/>512904N 0002344W -<br/>512905N 0002141W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3613735833,51.4846374722,609.6 -0.3956410556,51.4845450833,609.6 -0.3949547368,51.4811877781,609.6 -0.3947077047,51.4778067502,609.6 -0.3949014836,51.4744243673,609.6 -0.3955346944,51.471063,609.6 -0.3612565833,51.4711554167,609.6 -0.3613735833,51.4846374722,609.6 + + + + + + EGRU128D LONDON HEATHROW RWY 09R + <table border="1" cellpadding="1" cellspacing="0" row_id="7545" txt_name="LONDON HEATHROW RWY 09R"><tr><td>512728N 0003315W -<br/>512817N 0003316W -<br/>512817N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to<br/>512729N 0003112W -<br/>512728N 0003315W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5542044167,51.45779225,609.6 -0.5200781389,51.4579273056,609.6 -0.5225554954,51.4611347825,609.6 -0.5245850906,51.4644627941,609.6 -0.5261519863,51.4678869878,609.6 -0.5272446111,51.4713823056,609.6 -0.5543178889,51.4712743611,609.6 -0.5542044167,51.45779225,609.6 + + + + + + EGRU128E LONDON HEATHROW RWY 27L + <table border="1" cellpadding="1" cellspacing="0" row_id="7937" txt_name="LONDON HEATHROW RWY 27L"><tr><td>512819N 0002144W -<br/>512730N 0002144W -<br/>512730N 0002408W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to<br/>512819N 0002343W -<br/>512819N 0002144W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3622085,51.4719051944,609.6 -0.3953535278,51.4718188333,609.6 -0.3963867682,51.4683164757,609.6 -0.397895493,51.4648821005,609.6 -0.3998685359,51.4615408393,609.6 -0.4022913611,51.4583171389,609.6 -0.3620950278,51.4584231111,609.6 -0.3622085,51.4719051944,609.6 + + + + + + EGRU129A NORTHOLT + <table border="1" cellpadding="1" cellspacing="0" row_id="7976" txt_name="NORTHOLT"><tr><td>A circle, 2 NM radius, centred at 513310N 0002511W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4197222222,51.5860694194,609.6 -0.4252170925,51.5858928414,609.6 -0.4306535891,51.5853649835,609.6 -0.4359739627,51.584491453,609.6 -0.4411217051,51.5832815289,609.6 -0.4460421536,51.5817480627,609.6 -0.4506830738,51.5799073411,609.6 -0.4549952171,51.5777789117,609.6 -0.4589328445,51.5753853748,609.6 -0.4624542133,51.5727521418,609.6 -0.4655220189,51.5699071642,609.6 -0.4681037901,51.5668806359,609.6 -0.4701722306,51.5637046715,609.6 -0.4717055057,51.5604129644,609.6 -0.4726874696,51.5570404286,609.6 -0.4731078322,51.5536228274,609.6 -0.4729622633,51.5501963944,609.6 -0.4722524326,51.5467974485,609.6 -0.4709859873,51.5434620093,609.6 -0.4691764654,51.5402254156,609.6 -0.4668431476,51.5371219518,609.6 -0.4640108489,51.5341844852,609.6 -0.4607096516,51.5314441189,609.6 -0.4569745846,51.5289298638,609.6 -0.45284525,51.5266683326,609.6 -0.4483654033,51.5246834591,609.6 -0.4435824903,51.5229962465,609.6 -0.4385471456,51.521624546,609.6 -0.4333126589,51.5205828693,609.6 -0.4279344138,51.5198822356,609.6 -0.4224693049,51.5195300562,609.6 -0.4169751395,51.5195300562,609.6 -0.4115100306,51.5198822356,609.6 -0.4061317855,51.5205828693,609.6 -0.4008972988,51.521624546,609.6 -0.3958619541,51.5229962465,609.6 -0.3910790411,51.5246834591,609.6 -0.3865991945,51.5266683326,609.6 -0.3824698599,51.5289298638,609.6 -0.3787347928,51.5314441189,609.6 -0.3754335956,51.5341844852,609.6 -0.3726012968,51.5371219518,609.6 -0.3702679791,51.5402254156,609.6 -0.3684584572,51.5434620093,609.6 -0.3671920118,51.5467974485,609.6 -0.3664821812,51.5501963944,609.6 -0.3663366122,51.5536228274,609.6 -0.3667569749,51.5570404286,609.6 -0.3677389388,51.5604129644,609.6 -0.3692722138,51.5637046715,609.6 -0.3713406543,51.5668806359,609.6 -0.3739224255,51.5699071642,609.6 -0.3769902312,51.5727521418,609.6 -0.3805115999,51.5753853748,609.6 -0.3844492274,51.5777789117,609.6 -0.3887613706,51.5799073411,609.6 -0.3934022908,51.5817480627,609.6 -0.3983227393,51.5832815289,609.6 -0.4034704818,51.584491453,609.6 -0.4087908553,51.5853649835,609.6 -0.414227352,51.5858928414,609.6 -0.4197222222,51.5860694194,609.6 + + + + + + EGRU129B NORTHOLT RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7806" txt_name="NORTHOLT RWY 07"><tr><td>513150N 0002942W -<br/>513221N 0003000W -<br/>513244N 0002819W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to<br/>513214N 0002801W -<br/>513150N 0002942W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4949055556,51.5306527778,609.6 -0.466825,51.53710075,609.6 -0.468901124,51.5398120238,609.6 -0.4705770388,51.5426289526,609.6 -0.4718390278,51.5455286111,609.6 -0.4998722222,51.5390916667,609.6 -0.4949055556,51.5306527778,609.6 + + + + + + EGRU129C NORTHOLT RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7684" txt_name="NORTHOLT RWY 25"><tr><td>513430N 0002035W -<br/>513400N 0002017W -<br/>513335N 0002203W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to<br/>513406N 0002221W -<br/>513430N 0002035W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3429888889,51.5750055556,609.6 -0.3724551111,51.5682804444,609.6 -0.3704066466,51.5655610198,609.6 -0.3687601003,51.5627375531,609.6 -0.3675288056,51.5598330556,609.6 -0.3380138889,51.5665694444,609.6 -0.3429888889,51.5750055556,609.6 + + + + + + EGRU130A LONDON LUTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7505" txt_name="LONDON LUTON"><tr><td>A circle, 2.5 NM radius, centred at 515229N 0002206W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3684444444,51.9162427857,609.6 -0.3746532062,51.9160651122,609.6 -0.3808088511,51.9155336117,609.6 -0.3868587204,51.9146528312,609.6 -0.3927510676,51.9134303051,609.6 -0.3984355044,51.9118764909,609.6 -0.4038634347,51.9100046782,609.6 -0.4089884723,51.9078308751,609.6 -0.4137668395,51.9053736697,609.6 -0.4181577423,51.90265407,609.6 -0.4221237194,51.8996953238,609.6 -0.4256309617,51.8965227181,609.6 -0.4286495997,51.8931633624,609.6 -0.4311539569,51.8896459557,609.6 -0.4331227659,51.8860005403,609.6 -0.4345393464,51.8822582448,609.6 -0.4353917437,51.8784510169,609.6 -0.4356728262,51.8746113507,609.6 -0.4353803413,51.870772009,609.6 -0.4345169299,51.8669657435,609.6 -0.4330900986,51.8632250155,609.6 -0.4311121514,51.8595817194,609.6 -0.4286000794,51.8560669116,609.6 -0.4255754131,51.8527105458,609.6 -0.4220640341,51.8495412194,609.6 -0.4180959529,51.8465859299,609.6 -0.41370505,51.8438698469,609.6 -0.408928787,51.8414160983,609.6 -0.4038078861,51.8392455744,609.6 -0.3983859841,51.8373767517,609.6 -0.3927092619,51.8358255363,609.6 -0.386826053,51.8346051295,609.6 -0.3807864345,51.8337259165,609.6 -0.3746418038,51.8331953784,609.6 -0.3684444444,51.8330180294,609.6 -0.3622470851,51.8331953784,609.6 -0.3561024544,51.8337259165,609.6 -0.3500628358,51.8346051295,609.6 -0.344179627,51.8358255363,609.6 -0.3385029048,51.8373767517,609.6 -0.3330810028,51.8392455744,609.6 -0.3279601019,51.8414160983,609.6 -0.3231838389,51.8438698469,609.6 -0.318792936,51.8465859299,609.6 -0.3148248548,51.8495412194,609.6 -0.3113134758,51.8527105458,609.6 -0.3082888095,51.8560669116,609.6 -0.3057767375,51.8595817194,609.6 -0.3037987903,51.8632250155,609.6 -0.302371959,51.8669657435,609.6 -0.3015085476,51.870772009,609.6 -0.3012160627,51.8746113507,609.6 -0.3014971452,51.8784510169,609.6 -0.3023495425,51.8822582448,609.6 -0.303766123,51.8860005403,609.6 -0.3057349319,51.8896459557,609.6 -0.3082392892,51.8931633624,609.6 -0.3112579272,51.8965227181,609.6 -0.3147651695,51.8996953238,609.6 -0.3187311466,51.90265407,609.6 -0.3231220494,51.9053736697,609.6 -0.3279004166,51.9078308751,609.6 -0.3330254542,51.9100046782,609.6 -0.3384533845,51.9118764909,609.6 -0.3441378213,51.9134303051,609.6 -0.3500301685,51.9146528312,609.6 -0.3560800378,51.9155336117,609.6 -0.3622356827,51.9160651122,609.6 -0.3684444444,51.9162427857,609.6 + + + + + + EGRU130B LONDON LUTON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7526" txt_name="LONDON LUTON RWY 07"><tr><td>515120N 0002706W -<br/>515151N 0002720W -<br/>515204N 0002605W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to<br/>515133N 0002551W -<br/>515120N 0002706W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4515333333,51.8555694444,609.6 -0.4308439444,51.8591609444,609.6 -0.4324842643,51.8619845779,609.6 -0.4337918297,51.8648740476,609.6 -0.4347598056,51.8678143333,609.6 -0.4554361111,51.864225,609.6 -0.4515333333,51.8555694444,609.6 + + + + + + EGRU130C LONDON LUTON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7709" txt_name="LONDON LUTON RWY 25"><tr><td>515336N 0001711W -<br/>515305N 0001657W -<br/>515253N 0001808W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to<br/>515324N 0001822W -<br/>515336N 0001711W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2864888889,51.8934305556,609.6 -0.3060048333,51.8900711944,609.6 -0.3043708809,51.8872457884,609.6 -0.3030704243,51.8843548473,609.6 -0.3021101667,51.8814134167,609.6 -0.2825805556,51.884775,609.6 -0.2864888889,51.8934305556,609.6 + + + + + + EGRU131A ELSTREE + <table border="1" cellpadding="1" cellspacing="0" row_id="7624" txt_name="ELSTREE"><tr><td>A circle, 2 NM radius, centred at 513921N 0001933W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.32585,51.6891160539,609.6 -0.3313573375,51.6889394786,609.6 -0.3368061684,51.6884116286,609.6 -0.3421386119,51.6875381112,609.6 -0.3472980312,51.6863282054,609.6 -0.3522296393,51.6847947626,609.6 -0.356881083,51.6829540693,609.6 -0.3612030018,51.680825673,609.6 -0.365149553,51.6784321737,609.6 -0.3686788992,51.6757989826,609.6 -0.3717536515,51.672954051,609.6 -0.3743412651,51.6699275723,609.6 -0.3764143825,51.6667516608,609.6 -0.3779511197,51.6634600093,609.6 -0.378935295,51.6600875314,609.6 -0.3793565956,51.6566699898,609.6 -0.3792106819,51.6532436176,609.6 -0.3784992283,51.6498447329,609.6 -0.3772298997,51.6465093546,609.6 -0.3754162654,51.6432728209,609.6 -0.3730776505,51.6401694155,609.6 -0.3702389262,51.6372320048,609.6 -0.3669302437,51.6344916913,609.6 -0.3631867112,51.6319774852,609.6 -0.3590480206,51.6297159985,609.6 -0.3545580267,51.6277311645,609.6 -0.3497642823,51.6260439856,609.6 -0.3447175366,51.6246723128,609.6 -0.3394711997,51.6236306571,609.6 -0.3340807801,51.6229300376,609.6 -0.3286033007,51.6225778653,609.6 -0.3230966993,51.6225778653,609.6 -0.3176192199,51.6229300376,609.6 -0.3122288003,51.6236306571,609.6 -0.3069824634,51.6246723128,609.6 -0.3019357177,51.6260439856,609.6 -0.2971419733,51.6277311645,609.6 -0.2926519794,51.6297159985,609.6 -0.2885132888,51.6319774852,609.6 -0.2847697563,51.6344916913,609.6 -0.2814610738,51.6372320048,609.6 -0.2786223495,51.6401694155,609.6 -0.2762837346,51.6432728209,609.6 -0.2744701003,51.6465093546,609.6 -0.2732007717,51.6498447329,609.6 -0.2724893181,51.6532436176,609.6 -0.2723434044,51.6566699898,609.6 -0.272764705,51.6600875314,609.6 -0.2737488803,51.6634600093,609.6 -0.2752856175,51.6667516608,609.6 -0.2773587349,51.6699275723,609.6 -0.2799463485,51.672954051,609.6 -0.2830211008,51.6757989826,609.6 -0.286550447,51.6784321737,609.6 -0.2904969982,51.680825673,609.6 -0.294818917,51.6829540693,609.6 -0.2994703607,51.6847947626,609.6 -0.3044019688,51.6863282054,609.6 -0.3095613881,51.6875381112,609.6 -0.3148938316,51.6884116286,609.6 -0.3203426625,51.6889394786,609.6 -0.32585,51.6891160539,609.6 + + + + + + EGRU131B ELSTREE RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7536" txt_name="ELSTREE RWY 08"><tr><td>513834N 0002401W -<br/>513906N 0002410W -<br/>513916N 0002246W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to<br/>513844N 0002236W -<br/>513834N 0002401W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.40025,51.6427944444,609.6 -0.3767162778,51.6454770833,609.6 -0.3780102409,51.6483711888,609.6 -0.3788797194,51.6513260665,609.6 -0.3793175556,51.6543176667,609.6 -0.4028416667,51.6516361111,609.6 -0.40025,51.6427944444,609.6 + + + + + + EGRU131C ELSTREE RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8130" txt_name="ELSTREE RWY 26"><tr><td>514008N 0001505W -<br/>513936N 0001456W -<br/>513926N 0001621W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to<br/>513958N 0001630W -<br/>514008N 0001505W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.251425,51.6688083333,609.6 -0.2749615278,51.6661527222,609.6 -0.2736733649,51.6632575555,609.6 -0.2728102231,51.6603019573,609.6 -0.2723790556,51.65731,609.6 -0.2488333333,51.6599666667,609.6 -0.251425,51.6688083333,609.6 + + + + + + EGRU132A LONDON GATWICK + <table border="1" cellpadding="1" cellspacing="0" row_id="7550" txt_name="LONDON GATWICK"><tr><td>A circle, 2.5 NM radius, centred at 510853N 0001125W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1902777778,51.1896729688,609.6 -0.1963884086,51.1894952774,609.6 -0.2024467658,51.1889637232,609.6 -0.2084010264,51.1880828533,609.6 -0.214200265,51.1868602024,609.6 -0.2197948925,51.1853062283,609.6 -0.225137083,51.1834342212,609.6 -0.2301811851,51.1812601899,609.6 -0.2348841136,51.1788027231,609.6 -0.2392057194,51.1760828302,609.6 -0.2431091322,51.1731237601,609.6 -0.2465610756,51.1699508017,609.6 -0.2495321498,51.1665910662,609.6 -0.2519970809,51.1630732549,609.6 -0.2539349337,51.1594274128,609.6 -0.2553292873,51.1556846713,609.6 -0.2561683713,51.1518769815,609.6 -0.2564451617,51.1480368411,609.6 -0.2561574367,51.1441970168,609.6 -0.2553077906,51.1403902646,609.6 -0.2539036069,51.1366490502,609.6 -0.2519569908,51.1330052727,609.6 -0.2494846615,51.1294899933,609.6 -0.2465078063,51.1261331707,609.6 -0.243051896,51.1229634069,609.6 -0.2391464653,51.1200077046,609.6 -0.2348248596,51.1172912377,609.6 -0.2301239488,51.1148371386,609.6 -0.2250838137,51.1126663019,609.6 -0.2197474041,51.1107972077,609.6 -0.2141601747,51.1092457655,609.6 -0.2083696995,51.1080251793,609.6 -0.202425269,51.1071458364,609.6 -0.1963774741,51.1066152198,609.6 -0.1902777778,51.1064378445,609.6 -0.1841780815,51.1066152198,609.6 -0.1781302865,51.1071458364,609.6 -0.1721858561,51.1080251793,609.6 -0.1663953808,51.1092457655,609.6 -0.1608081514,51.1107972077,609.6 -0.1554717418,51.1126663019,609.6 -0.1504316067,51.1148371386,609.6 -0.145730696,51.1172912377,609.6 -0.1414090902,51.1200077046,609.6 -0.1375036596,51.1229634069,609.6 -0.1340477492,51.1261331707,609.6 -0.131070894,51.1294899933,609.6 -0.1285985648,51.1330052727,609.6 -0.1266519486,51.1366490502,609.6 -0.1252477649,51.1403902646,609.6 -0.1243981188,51.1441970168,609.6 -0.1241103939,51.1480368411,609.6 -0.1243871843,51.1518769815,609.6 -0.1252262682,51.1556846713,609.6 -0.1266206218,51.1594274128,609.6 -0.1285584746,51.1630732549,609.6 -0.1310234057,51.1665910662,609.6 -0.13399448,51.1699508017,609.6 -0.1374464234,51.1731237601,609.6 -0.1413498362,51.1760828302,609.6 -0.1456714419,51.1788027231,609.6 -0.1503743705,51.1812601899,609.6 -0.1554184725,51.1834342212,609.6 -0.1607606631,51.1853062283,609.6 -0.1663552906,51.1868602024,609.6 -0.1721545292,51.1880828533,609.6 -0.1781087898,51.1889637232,609.6 -0.1841671469,51.1894952774,609.6 -0.1902777778,51.1896729688,609.6 + + + + + + EGRU132B LONDON GATWICK RWY 08L + <table border="1" cellpadding="1" cellspacing="0" row_id="7974" txt_name="LONDON GATWICK RWY 08L"><tr><td>510801N 0001635W -<br/>510832N 0001646W -<br/>510844N 0001523W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to<br/>510812N 0001514W -<br/>510801N 0001635W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2763583333,51.1334722222,609.6 -0.2538749722,51.1365861111,609.6 -0.2550266082,51.1395019494,609.6 -0.255840969,51.1424624516,609.6 -0.25631375,51.1454521944,609.6 -0.2794138889,51.1422527778,609.6 -0.2763583333,51.1334722222,609.6 + + + + + + EGRU132C LONDON GATWICK RWY 26R + <table border="1" cellpadding="1" cellspacing="0" row_id="8157" txt_name="LONDON GATWICK RWY 26R"><tr><td>510954N 0000652W -<br/>510922N 0000641W -<br/>510916N 0000730W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to<br/>510947N 0000743W -<br/>510954N 0000652W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1143222222,51.1650083333,609.6 -0.1285487778,51.1630574722,609.6 -0.126990203,51.1602170511,609.6 -0.1257617811,51.1573133081,609.6 -0.1248698611,51.1543613889,609.6 -0.1112583333,51.1562277778,609.6 -0.1143222222,51.1650083333,609.6 + + + + + + EGRU132D LONDON GATWICK RWY 08R + <table border="1" cellpadding="1" cellspacing="0" row_id="7858" txt_name="LONDON GATWICK RWY 08R"><tr><td>510755N 0001630W -<br/>510826N 0001641W -<br/>510837N 0001522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to<br/>510806N 0001511W -<br/>510755N 0001630W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2750777778,51.1318138889,609.6 -0.2530278889,51.1348706667,609.6 -0.2543771033,51.1377494398,609.6 -0.2553931703,51.1406818913,609.6 -0.25607075,51.1436527778,609.6 -0.2781333333,51.1405944444,609.6 -0.2750777778,51.1318138889,609.6 + + + + + + EGRU132E LONDON GATWICK RWY 26L + <table border="1" cellpadding="1" cellspacing="0" row_id="8182" txt_name="LONDON GATWICK RWY 26L"><tr><td>510953N 0000613W -<br/>510921N 0000602W -<br/>510909N 0000728W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to<br/>510941N 0000739W -<br/>510953N 0000613W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1036388889,51.1646583333,609.6 -0.1275807778,51.1613735,609.6 -0.1262195947,51.1584972883,609.6 -0.1251916959,51.1555668638,609.6 -0.1245023611,51.1525974722,609.6 -0.100575,51.1558805556,609.6 -0.1036388889,51.1646583333,609.6 + + + + + + EGRU133A REDHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="8115" txt_name="REDHILL"><tr><td>511134N 0001048W thence clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511230N 0000511W -<br/>511134N 0001048W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.18,51.1927777778,609.6 -0.0863888889,51.2083333333,609.6 -0.0857783081,51.2117007276,609.6 -0.0857454411,51.2150907095,609.6 -0.0862619904,51.2184651944,609.6 -0.0873227125,51.2217891473,609.6 -0.0889167081,51.2250280504,609.6 -0.091027531,51.2281482618,609.6 -0.0936333542,51.231117366,609.6 -0.0967071931,51.2339045112,609.6 -0.1002171832,51.2364807312,609.6 -0.1041269087,51.2388192469,609.6 -0.1083957801,51.2408957465,609.6 -0.1129794553,51.242688639,609.6 -0.1178303017,51.24417928,609.6 -0.1228978922,51.2453521666,609.6 -0.1281295323,51.2461950995,609.6 -0.1334708104,51.2466993108,609.6 -0.1388661674,51.2468595556,609.6 -0.144259478,51.246674167,609.6 -0.1495946383,51.2461450733,609.6 -0.1548161531,51.2452777785,609.6 -0.1598697169,51.2440813036,609.6 -0.1647027819,51.2425680934,609.6 -0.1692651072,51.2407538854,609.6 -0.1735092831,51.2386575454,609.6 -0.1773912259,51.2363008705,609.6 -0.1808706361,51.233708361,609.6 -0.1839114173,51.230906965,609.6 -0.1864820495,51.2279257965,609.6 -0.1885559151,51.2247958322,609.6 -0.1901115721,51.2215495885,609.6 -0.1911329731,51.2182207829,609.6 -0.1916096276,51.2148439831,609.6 -0.1915367066,51.2114542476,609.6 -0.1909150876,51.2080867616,609.6 -0.1897513404,51.2047764719,609.6 -0.1880576543,51.2015577241,609.6 -0.1858517068,51.1984639072,609.6 -0.1831564762,51.1955271077,609.6 -0.18,51.1927777778,609.6 + + + + + + EGRU133B REDHILL RWY 07L + <table border="1" cellpadding="1" cellspacing="0" row_id="7890" txt_name="REDHILL RWY 07L"><tr><td>511150N 0001237W -<br/>511221N 0001251W -<br/>511235N 0001129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511204N 0001116W -<br/>511150N 0001237W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2102416667,51.1971527778,609.6 -0.1877980556,51.2010925556,609.6 -0.1893926122,51.2039255796,609.6 -0.1905742304,51.2068373717,609.6 -0.1913332222,51.2098042222,609.6 -0.2140805556,51.2058111111,609.6 -0.2102416667,51.1971527778,609.6 + + + + + + EGRU133C REDHILL RWY 25R + <table border="1" cellpadding="1" cellspacing="0" row_id="7892" txt_name="REDHILL RWY 25R"><tr><td>511354N 0000400W -<br/>511323N 0000347W -<br/>511308N 0000511W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511339N 0000526W -<br/>511354N 0000400W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0667972222,51.231575,609.6 -0.0904669444,51.2274489722,609.6 -0.0886741747,51.2246628442,609.6 -0.0872889642,51.2217865477,609.6 -0.0863225278,51.2188435278,609.6 -0.0629555556,51.2229166667,609.6 -0.0667972222,51.231575,609.6 + + + + + + EGRU133D REDHILL RWY 07R + <table border="1" cellpadding="1" cellspacing="0" row_id="7627" txt_name="REDHILL RWY 07R"><tr><td>511146N 0001243W -<br/>511218N 0001257W -<br/>511233N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511202N 0001115W -<br/>511146N 0001243W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2119305556,51.1962361111,609.6 -0.1873991111,51.2004910278,609.6 -0.18908136,51.2033034861,609.6 -0.1903533425,51.2061997519,609.6 -0.1912046389,51.20915625,609.6 -0.2157277778,51.2049027778,609.6 -0.2119305556,51.1962361111,609.6 + + + + + + EGRU133E REDHILL RWY 25L + <table border="1" cellpadding="1" cellspacing="0" row_id="7520" txt_name="REDHILL RWY 25L"><tr><td>511351N 0000355W -<br/>511320N 0000342W -<br/>511305N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511336N 0000524W -<br/>511351N 0000355W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0653694444,51.2308888889,609.6 -0.0899130833,51.22666225,609.6 -0.0882358648,51.2238484928,609.6 -0.0869696108,51.2209512348,609.6 -0.0861245556,51.2179940833,609.6 -0.0615722222,51.2222222222,609.6 -0.0653694444,51.2308888889,609.6 + + + + + + EGRU133F REDHILL RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7682" txt_name="REDHILL RWY 18"><tr><td>511545N 0000848W -<br/>511545N 0000756W -<br/>511448N 0000758W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511447N 0000849W -<br/>511545N 0000848W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1465555556,51.2626111111,609.6 -0.1470106389,51.2464652222,609.6 -0.1422509249,51.2468036602,609.6 -0.1374619454,51.2468710493,609.6 -0.1326828333,51.2466668333,609.6 -0.1322333333,51.2624527778,609.6 -0.1465555556,51.2626111111,609.6 + + + + + + EGRU133G REDHILL RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7906" txt_name="REDHILL RWY 36"><tr><td>510959N 0000806W -<br/>510959N 0000857W -<br/>511153N 0000854W -<br/>511202N 0000802W -<br/>510959N 0000806W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1349666667,51.1662944444,609.6 -0.1339975833,51.2004327778,609.6 -0.1483735833,51.19804275,609.6 -0.1492611111,51.1664555556,609.6 -0.1349666667,51.1662944444,609.6 + + + + + + EGRU133H REDHILL RWY H07 + <table border="1" cellpadding="1" cellspacing="0" row_id="8124" txt_name="REDHILL RWY H07"><tr><td>511147N 0001226W -<br/>511218N 0001240W -<br/>511230N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511159N 0001113W -<br/>511147N 0001226W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2073083333,51.1962888889,609.6 -0.1869276111,51.1998197778,609.6 -0.1887082862,51.2026087033,609.6 -0.1900816288,51.2054871169,609.6 -0.1910363889,51.2084315833,609.6 -0.2111,51.2049555556,609.6 -0.2073083333,51.1962888889,609.6 + + + + + + EGRU133I REDHILL RWY H25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8070" txt_name="REDHILL RWY H25"><tr><td>511345N 0000415W -<br/>511314N 0000401W -<br/>511302N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511333N 0000522W -<br/>511345N 0000415W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0707138889,51.2291944444,609.6 -0.0894569722,51.2259695,609.6 -0.0878808339,51.2231321936,609.6 -0.0867187109,51.2202171888,609.6 -0.0859799722,51.21724825,609.6 -0.0669194444,51.2205277778,609.6 -0.0707138889,51.2291944444,609.6 + + + + + + EGRU133J REDHILL RWY H18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7816" txt_name="REDHILL RWY H18"><tr><td>511528N 0000927W -<br/>511530N 0000836W -<br/>511449N 0000832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to<br/>511442N 0000923W -<br/>511528N 0000927W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.157575,51.2578166667,609.6 -0.1562663333,51.2449930556,609.6 -0.1516398746,51.2458686873,609.6 -0.146905405,51.2464759748,609.6 -0.1421024444,51.2468101389,609.6 -0.1432805556,51.2583888889,609.6 -0.157575,51.2578166667,609.6 + + + + + + EGRU133K REDHILL RWY H36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7900" txt_name="REDHILL RWY H36"><tr><td>511002N 0000802W -<br/>511000N 0000854W -<br/>511151N 0000905W -<br/>511200N 0000814W -<br/>511002N 0000802W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1340222222,51.1672388889,609.6 -0.1373332778,51.1998783889,609.6 -0.1514294722,51.1975344444,609.6 -0.1482888889,51.1666666667,609.6 -0.1340222222,51.1672388889,609.6 + + + + + + EGRU134A BIGGIN HILL + <table border="1" cellpadding="1" cellspacing="0" row_id="7821" txt_name="BIGGIN HILL"><tr><td>A circle, 2.5 NM radius, centred at 511951N 0000157E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0325,51.3724494398,609.6 0.02636507,51.372271753,609.6 0.0202826224,51.3717402124,609.6 0.0143046872,51.370859365,609.6 0.008482393,51.3696367457,609.6 0.0028655268,51.368082812,609.6 -0.0024978947,51.3662108541,609.6 -0.0075620381,51.3640368805,609.6 -0.012283647,51.3615794797,609.6 -0.0166224123,51.3588596609,609.6 -0.0205413175,51.3559006727,609.6 -0.0240069543,51.3527278033,609.6 -0.0269898066,51.3493681637,609.6 -0.0294645007,51.3458504545,609.6 -0.0314100192,51.3422047201,609.6 -0.0328098769,51.3384620911,609.6 -0.0336522578,51.3346545178,609.6 -0.0339301114,51.330814497,609.6 -0.033641208,51.3269747944,609.6 -0.0327881536,51.3231681648,609.6 -0.0313783621,51.3194270729,609.6 -0.0294239879,51.3157834167,609.6 -0.0269418177,51.3122682561,609.6 -0.0239531235,51.3089115485,609.6 -0.0204834779,51.3057418948,609.6 -0.0165625336,51.3027862964,609.6 -0.0122237683,51.3000699262,609.6 -0.0075041985,51.2976159153,609.6 -0.0024440638,51.2954451573,609.6 0.0029135158,51.2935761314,609.6 0.0085229059,51.2920247463,609.6 0.0143363443,51.2908042052,609.6 0.0203043458,51.289924895,609.6 0.0263761198,51.2893942982,609.6 0.0325,51.2892169295,609.6 0.0386238802,51.2893942982,609.6 0.0446956542,51.289924895,609.6 0.0506636557,51.2908042052,609.6 0.0564770941,51.2920247463,609.6 0.0620864842,51.2935761314,609.6 0.0674440638,51.2954451573,609.6 0.0725041985,51.2976159153,609.6 0.0772237683,51.3000699262,609.6 0.0815625336,51.3027862964,609.6 0.0854834779,51.3057418948,609.6 0.0889531235,51.3089115485,609.6 0.0919418177,51.3122682561,609.6 0.0944239879,51.3157834167,609.6 0.0963783621,51.3194270729,609.6 0.0977881536,51.3231681648,609.6 0.098641208,51.3269747944,609.6 0.0989301114,51.330814497,609.6 0.0986522578,51.3346545178,609.6 0.0978098769,51.3384620911,609.6 0.0964100192,51.3422047201,609.6 0.0944645007,51.3458504545,609.6 0.0919898066,51.3493681637,609.6 0.0890069543,51.3527278033,609.6 0.0855413175,51.3559006727,609.6 0.0816224123,51.3588596609,609.6 0.077283647,51.3615794797,609.6 0.0725620381,51.3640368805,609.6 0.0674978947,51.3662108541,609.6 0.0621344732,51.368082812,609.6 0.056517607,51.3696367457,609.6 0.0506953128,51.370859365,609.6 0.0447173776,51.3717402124,609.6 0.03863493,51.372271753,609.6 0.0325,51.3724494398,609.6 + + + + + + EGRU134B BIGGIN HILL RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7527" txt_name="BIGGIN HILL RWY 03"><tr><td>511700N 0000013E -<br/>511714N 0000033W -<br/>511744N 0000010W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to<br/>511730N 0000037E -<br/>511700N 0000013E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0037444444,51.2832027778,609.6 0.0102089167,51.2916319722,609.6 0.0057608933,51.2927401761,609.6 0.0014515666,51.2940463129,609.6 -0.0026966944,51.2955436111,609.6 -0.0091694444,51.2871,609.6 0.0037444444,51.2832027778,609.6 + + + + + + EGRU134C BIGGIN HILL RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7564" txt_name="BIGGIN HILL RWY 21"><tr><td>512251N 0000346E -<br/>512236N 0000432E -<br/>512158N 0000403E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to<br/>512212N 0000316E -<br/>512251N 0000346E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0627277778,51.3806944444,609.6 0.0545643611,51.3700889167,609.6 0.05902709,51.368990418,609.6 0.0633514721,51.3676932629,609.6 0.0675149722,51.3662042222,609.6 0.0756722222,51.3767972222,609.6 0.0627277778,51.3806944444,609.6 + + + + + + EGRU135A LONDON CITY + <table border="1" cellpadding="1" cellspacing="0" row_id="7907" txt_name="LONDON CITY"><tr><td>A circle, 2 NM radius, centred at 513019N 0000319E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0551777778,51.5385224685,609.6 0.049688635,51.5383458893,609.6 0.0442578048,51.5378180277,609.6 0.0389429762,51.5369444912,609.6 0.0338005981,51.5357345586,609.6 0.0288852764,51.5342010816,609.6 0.0242491907,51.5323603469,609.6 0.0199415384,51.5302319023,609.6 0.0160080105,51.527838348,609.6 0.0124903067,51.5252050956,609.6 0.0094256923,51.5223600968,609.6 0.0068466052,51.5193335456,609.6 0.0047803132,51.5161575568,609.6 0.0032486287,51.512865824,609.6 0.0022676808,51.5094932614,609.6 0.001847749,51.5060756327,609.6 0.0019931596,51.5026491717,609.6 0.0027022447,51.4992501975,609.6 0.0039673655,51.4959147301,609.6 0.0057749982,51.4926781088,609.6 0.0081058824,51.489574618,609.6 0.0109352292,51.4866371256,609.6 0.0142329877,51.4838967349,609.6 0.0179641657,51.4813824572,609.6 0.0220892021,51.4791209055,609.6 0.0265643871,51.4771360138,609.6 0.0313423241,51.4754487856,609.6 0.0363724312,51.4740770724,609.6 0.0416014737,51.473035386,609.6 0.0469741258,51.4723347457,609.6 0.0524335517,51.471982563,609.6 0.0579220039,51.471982563,609.6 0.0633814298,51.4723347457,609.6 0.0687540818,51.473035386,609.6 0.0739831244,51.4740770724,609.6 0.0790132314,51.4754487856,609.6 0.0837911685,51.4771360138,609.6 0.0882663534,51.4791209055,609.6 0.0923913899,51.4813824572,609.6 0.0961225678,51.4838967349,609.6 0.0994203263,51.4866371256,609.6 0.1022496732,51.489574618,609.6 0.1045805574,51.4926781088,609.6 0.1063881901,51.4959147301,609.6 0.1076533108,51.4992501975,609.6 0.1083623959,51.5026491717,609.6 0.1085078065,51.5060756327,609.6 0.1080878748,51.5094932614,609.6 0.1071069268,51.512865824,609.6 0.1055752423,51.5161575568,609.6 0.1035089504,51.5193335456,609.6 0.1009298632,51.5223600968,609.6 0.0978652489,51.5252050956,609.6 0.094347545,51.527838348,609.6 0.0904140172,51.5302319023,609.6 0.0861063648,51.5323603469,609.6 0.0814702792,51.5342010816,609.6 0.0765549574,51.5357345586,609.6 0.0714125794,51.5369444912,609.6 0.0660977508,51.5378180277,609.6 0.0606669206,51.5383458893,609.6 0.0551777778,51.5385224685,609.6 + + + + + + EGRU135B LONDON CITY RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8014" txt_name="LONDON CITY RWY 09"><tr><td>513012N 0000136W -<br/>513044N 0000133W -<br/>513041N 0000010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to<br/>513009N 0000007E -<br/>513012N 0000136W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0265288333,51.5032755556,609.6 0.0020265,51.5023953889,609.6 0.0018316307,51.5053971176,609.6 0.0020711489,51.5083975865,609.6 0.0027431944,51.5113723611,609.6 -0.0258050833,51.5122523333,609.6 -0.0265288333,51.5032755556,609.6 + + + + + + EGRU135C LONDON CITY RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7703" txt_name="LONDON CITY RWY 27"><tr><td>513026N 0000814E -<br/>512953N 0000811E -<br/>512957N 0000627E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to<br/>513029N 0000630E -<br/>513026N 0000814E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1372346667,51.5071330556,609.6 0.1083335278,51.5080571389,609.6 0.1085236627,51.5050552868,609.6 0.1082794163,51.5020549588,609.6 0.1076028611,51.4990805833,609.6 0.136511,51.4981562778,609.6 0.1372346667,51.5071330556,609.6 + + + + + + EGRU136A STAPLEFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="7824" txt_name="STAPLEFORD"><tr><td>A circle, 2 NM radius, centred at 513909N 0000922E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1560083333,51.6857966284,609.6 0.1505013986,51.685620053,609.6 0.1450529662,51.6850922028,609.6 0.1397209126,51.684218685,609.6 0.1345618705,51.6830087786,609.6 0.129630623,51.681475335,609.6 0.1249795192,51.6796346408,609.6 0.1206579162,51.6775062434,609.6 0.1167116533,51.6751127429,609.6 0.1131825649,51.6724795505,609.6 0.110108037,51.6696346173,609.6 0.1075206121,51.6666081371,609.6 0.1054476458,51.6634322239,609.6 0.1039110205,51.6601405706,609.6 0.1029269166,51.6567680908,609.6 0.1025056463,51.6533505473,609.6 0.1026515488,51.6499241731,609.6 0.1033629501,51.6465252864,609.6 0.1046321855,51.6431899062,609.6 0.1064456869,51.6399533706,609.6 0.1087841307,51.6368499633,609.6 0.1116226474,51.6339125508,609.6 0.1149310881,51.6311722356,609.6 0.1186743472,51.6286580279,609.6 0.1228127354,51.6263965398,609.6 0.1273024016,51.6244117045,609.6 0.132095796,51.6227245245,609.6 0.1371421734,51.6213528508,609.6 0.1423881274,51.6203111944,609.6 0.1477781538,51.6196105745,609.6 0.1532552335,51.619258402,609.6 0.1587614331,51.619258402,609.6 0.1642385129,51.6196105745,609.6 0.1696285392,51.6203111944,609.6 0.1748744933,51.6213528508,609.6 0.1799208706,51.6227245245,609.6 0.1847142651,51.6244117045,609.6 0.1892039312,51.6263965398,609.6 0.1933423195,51.6286580279,609.6 0.1970855786,51.6311722356,609.6 0.2003940193,51.6339125508,609.6 0.2032325359,51.6368499633,609.6 0.2055709798,51.6399533706,609.6 0.2073844812,51.6431899062,609.6 0.2086537166,51.6465252864,609.6 0.2093651178,51.6499241731,609.6 0.2095110204,51.6533505473,609.6 0.2090897501,51.6567680908,609.6 0.2081056462,51.6601405706,609.6 0.2065690208,51.6634322239,609.6 0.2044960546,51.6666081371,609.6 0.2019086297,51.6696346173,609.6 0.1988341018,51.6724795505,609.6 0.1953050134,51.6751127429,609.6 0.1913587504,51.6775062434,609.6 0.1870371475,51.6796346408,609.6 0.1823860437,51.681475335,609.6 0.1774547962,51.6830087786,609.6 0.172295754,51.684218685,609.6 0.1669637005,51.6850922028,609.6 0.161515268,51.685620053,609.6 0.1560083333,51.6857966284,609.6 + + + + + + EGRU136B STAPLEFORD RWY 03L + <table border="1" cellpadding="1" cellspacing="0" row_id="7861" txt_name="STAPLEFORD RWY 03L"><tr><td>513634N 0000654E -<br/>513653N 0000612E -<br/>513743N 0000708E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to<br/>513724N 0000750E -<br/>513634N 0000654E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.114975,51.6095305556,609.6 0.1306218889,51.6232006389,609.6 0.1264803317,51.6247434871,609.6 0.1225788083,51.6265123207,609.6 0.1189490556,51.62849275,609.6 0.1032222222,51.61475,609.6 0.114975,51.6095305556,609.6 + + + + + + EGRU136C STAPLEFORD RWY 21R + <table border="1" cellpadding="1" cellspacing="0" row_id="8133" txt_name="STAPLEFORD RWY 21R"><tr><td>514140N 0001141E -<br/>514122N 0001223E -<br/>514037N 0001132E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to<br/>514056N 0001050E -<br/>514140N 0001141E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1946944444,51.6945361111,609.6 0.1804416944,51.6821273889,609.6 0.1846372067,51.6806366835,609.6 0.1885991606,51.6789167892,609.6 0.1922952778,51.67698175,609.6 0.2064694444,51.6893194444,609.6 0.1946944444,51.6945361111,609.6 + + + + + + EGRU136D STAPLEFORD RWY 03R + <table border="1" cellpadding="1" cellspacing="0" row_id="7558" txt_name="STAPLEFORD RWY 03R"><tr><td>513634N 0000656E -<br/>513652N 0000613E -<br/>513742N 0000710E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to<br/>513723N 0000752E -<br/>513634N 0000656E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1154222222,51.6093166667,609.6 0.1311190278,51.623036,609.6 0.126951311,51.6245517675,609.6 0.1230198351,51.6262951166,609.6 0.1193565833,51.6282518611,609.6 0.1036666667,51.6145361111,609.6 0.1154222222,51.6093166667,609.6 + + + + + + EGRU136E STAPLEFORD RWY 21L + <table border="1" cellpadding="1" cellspacing="0" row_id="7721" txt_name="STAPLEFORD RWY 21L"><tr><td>514140N 0001143E -<br/>514121N 0001225E -<br/>514036N 0001134E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to<br/>514055N 0001051E -<br/>514140N 0001143E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1951388889,51.6943527778,609.6 0.1809234167,51.6819718056,609.6 0.1850942614,51.6804547511,609.6 0.1890278444,51.678710016,609.6 0.1926921111,51.6767518333,609.6 0.2069138889,51.6891361111,609.6 0.1951388889,51.6943527778,609.6 + + + + + + EGRU137A LONDON STANSTED + <table border="1" cellpadding="1" cellspacing="0" row_id="7979" txt_name="LONDON STANSTED"><tr><td>A circle, 2.5 NM radius, centred at 515306N 0001406E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.235,51.9266121564,609.6 0.2287898076,51.9264344831,609.6 0.2226327443,51.9259029834,609.6 0.2165814812,51.9250222041,609.6 0.2106877765,51.9237996799,609.6 0.2050020304,51.9222458679,609.6 0.1995728501,51.920374058,609.6 0.1944466326,51.9182002582,609.6 0.1896671656,51.9157430564,609.6 0.1852752525,51.9130234609,609.6 0.1813083633,51.9100647192,609.6 0.1778003149,51.9068921185,609.6 0.1747809834,51.9035327683,609.6 0.1722760514,51.9000153673,609.6 0.1703067912,51.896369958,609.6 0.1688898867,51.8926276688,609.6 0.1680372953,51.8888204475,609.6 0.1677561503,51.8849807881,609.6 0.1680487046,51.8811414532,609.6 0.1689123167,51.8773351946,609.6 0.1703394781,51.8735944735,609.6 0.1723178822,51.8699511843,609.6 0.1748305335,51.8664363832,609.6 0.1778558969,51.863080024,609.6 0.1813680845,51.8599107037,609.6 0.1853370792,51.8569554202,609.6 0.1897289923,51.8542393427,609.6 0.1945063538,51.851785599,609.6 0.1996284322,51.8496150796,609.6 0.2050515805,51.8477462608,609.6 0.2107296074,51.8461950486,609.6 0.2166141682,51.8449746444,609.6 0.2226551744,51.8440954332,609.6 0.2288012169,51.8435648963,609.6 0.235,51.8433875477,609.6 0.2411987831,51.8435648963,609.6 0.2473448256,51.8440954332,609.6 0.2533858318,51.8449746444,609.6 0.2592703926,51.8461950486,609.6 0.2649484195,51.8477462608,609.6 0.2703715678,51.8496150796,609.6 0.2754936462,51.851785599,609.6 0.2802710077,51.8542393427,609.6 0.2846629208,51.8569554202,609.6 0.2886319155,51.8599107037,609.6 0.2921441031,51.863080024,609.6 0.2951694665,51.8664363832,609.6 0.2976821178,51.8699511843,609.6 0.2996605219,51.8735944735,609.6 0.3010876833,51.8773351946,609.6 0.3019512954,51.8811414532,609.6 0.3022438497,51.8849807881,609.6 0.3019627047,51.8888204475,609.6 0.3011101133,51.8926276688,609.6 0.2996932088,51.896369958,609.6 0.2977239486,51.9000153673,609.6 0.2952190166,51.9035327683,609.6 0.2921996851,51.9068921185,609.6 0.2886916367,51.9100647192,609.6 0.2847247475,51.9130234609,609.6 0.2803328344,51.9157430564,609.6 0.2755533674,51.9182002582,609.6 0.2704271499,51.920374058,609.6 0.2649979696,51.9222458679,609.6 0.2593122235,51.9237996799,609.6 0.2534185188,51.9250222041,609.6 0.2473672557,51.9259029834,609.6 0.2412101924,51.9264344831,609.6 0.235,51.9266121564,609.6 + + + + + + EGRU137B LONDON STANSTED RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7603" txt_name="LONDON STANSTED RWY 04"><tr><td>515028N 0001044E -<br/>515050N 0001005E -<br/>515128N 0001103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to<br/>515106N 0001141E -<br/>515028N 0001044E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1788194444,51.8410361111,609.6 0.1947456944,51.8516743056,609.6 0.1909710506,51.8535562167,609.6 0.187424914,51.8556015888,609.6 0.1841257222,51.8577998056,609.6 0.1681888889,51.8471527778,609.6 0.1788194444,51.8410361111,609.6 + + + + + + EGRU137C LONDON STANSTED RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7719" txt_name="LONDON STANSTED RWY 22"><tr><td>515552N 0001739E -<br/>515530N 0001817E -<br/>515444N 0001709E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to<br/>515506N 0001630E -<br/>515552N 0001739E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.2941833333,51.9311305556,609.6 0.2750736667,51.9184224444,609.6 0.2788639154,51.916548197,609.6 0.2824255347,51.9145097839,609.6 0.28574,51.9123178333,609.6 0.3048388889,51.9250166667,609.6 0.2941833333,51.9311305556,609.6 + + + + + + EGRU138A ANDREWSFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="7531" txt_name="ANDREWSFIELD"><tr><td>A circle, 2 NM radius, centred at 515342N 0002657E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4491666667,51.9282896919,609.6 0.4436301033,51.9281131227,609.6 0.4381523581,51.927585291,609.6 0.4327916201,51.926711804,609.6 0.4276048275,51.9255019406,609.6 0.422647059,51.9239685519,609.6 0.417970946,51.922127924,609.6 0.4136261113,51.9199996043,609.6 0.4096586409,51.9176061921,609.6 0.4061105941,51.9149730981,609.6 0.4030195576,51.9121282729,609.6 0.4004182481,51.9091019091,609.6 0.3983341674,51.90592612,609.6 0.3967893144,51.9026345974,609.6 0.3957999552,51.8992622536,609.6 0.3953764561,51.8958448503,609.6 0.395523178,51.8924186188,609.6 0.3962384364,51.889019876,609.6 0.3975145241,51.885684639,609.6 0.3993377987,51.8824482445,609.6 0.4016888316,51.8793449744,609.6 0.4045426185,51.8764076934,609.6 0.4078688481,51.8736675024,609.6 0.4116322255,51.87115341,609.6 0.4157928483,51.8688920266,609.6 0.4203066295,51.866907284,609.6 0.4251257647,51.8652201834,609.6 0.4301992364,51.8638485746,609.6 0.4354733526,51.8628069678,609.6 0.4408923117,51.8621063813,609.6 0.4463987898,51.8617542257,609.6 0.4519345435,51.8617542257,609.6 0.4574410216,51.8621063813,609.6 0.4628599807,51.8628069678,609.6 0.4681340969,51.8638485746,609.6 0.4732075687,51.8652201834,609.6 0.4780267038,51.866907284,609.6 0.4825404851,51.8688920266,609.6 0.4867011078,51.87115341,609.6 0.4904644852,51.8736675024,609.6 0.4937907148,51.8764076934,609.6 0.4966445018,51.8793449744,609.6 0.4989955347,51.8824482445,609.6 0.5008188092,51.885684639,609.6 0.502094897,51.889019876,609.6 0.5028101553,51.8924186188,609.6 0.5029568773,51.8958448503,609.6 0.5025333781,51.8992622536,609.6 0.5015440189,51.9026345974,609.6 0.4999991659,51.90592612,609.6 0.4979150853,51.9091019091,609.6 0.4953137757,51.9121282729,609.6 0.4922227392,51.9149730981,609.6 0.4886746924,51.9176061921,609.6 0.484707222,51.9199996043,609.6 0.4803623874,51.922127924,609.6 0.4756862743,51.9239685519,609.6 0.4707285058,51.9255019406,609.6 0.4655417132,51.926711804,609.6 0.4601809752,51.927585291,609.6 0.45470323,51.9281131227,609.6 0.4491666667,51.9282896919,609.6 + + + + + + EGRU138B ANDREWSFIELD RWY 09L + <table border="1" cellpadding="1" cellspacing="0" row_id="7621" txt_name="ANDREWSFIELD RWY 09L"><tr><td>515311N 0002223E -<br/>515343N 0002219E -<br/>515348N 0002344E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to<br/>515316N 0002348E -<br/>515311N 0002223E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.3730888889,51.8864027778,609.6 0.3966865556,51.88766425,609.6 0.3958296993,51.8906213139,609.6 0.3954070986,51.8936141315,609.6 0.3954222778,51.8966183333,609.6 0.3718527778,51.8953583333,609.6 0.3730888889,51.8864027778,609.6 + + + + + + EGRU138C ANDREWSFIELD RWY 27R + <table border="1" cellpadding="1" cellspacing="0" row_id="7980" txt_name="ANDREWSFIELD RWY 27R"><tr><td>515413N 0003137E -<br/>515341N 0003142E -<br/>515336N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to<br/>515408N 0003006E -<br/>515413N 0003137E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5269916667,51.9035638889,609.6 0.5016900556,51.9022398056,609.6 0.5025295237,51.8992807816,609.6 0.502934256,51.8962869854,609.6 0.5029010556,51.8932828056,609.6 0.5282305556,51.8946083333,609.6 0.5269916667,51.9035638889,609.6 + + + + + + EGRU138D ANDREWSFIELD RWY 09R + <table border="1" cellpadding="1" cellspacing="0" row_id="7568" txt_name="ANDREWSFIELD RWY 09R"><tr><td>515310N 0002223E -<br/>515342N 0002218E -<br/>515347N 0002343E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to<br/>515315N 0002348E -<br/>515310N 0002223E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.3729722222,51.8861333333,609.6 0.3967850556,51.8873999167,609.6 0.3958892902,51.8903525916,609.6 0.3954272954,51.8933432088,609.6 0.3954029167,51.8963474167,609.6 0.3717416667,51.8950888889,609.6 0.3729722222,51.8861333333,609.6 + + + + + + EGRU138E ANDREWSFIELD RWY 27L + <table border="1" cellpadding="1" cellspacing="0" row_id="8161" txt_name="ANDREWSFIELD RWY 27L"><tr><td>515412N 0003137E -<br/>515340N 0003142E -<br/>515335N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to<br/>515407N 0003006E -<br/>515412N 0003137E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5270416667,51.9032611111,609.6 0.50179325,51.9019466389,609.6 0.502589532,51.8989830515,609.6 0.5029506279,51.8959871214,609.6 0.5028736667,51.89298325,609.6 0.5282722222,51.8943055556,609.6 0.5270416667,51.9032611111,609.6 + + + + + + EGRU139A ROCHESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="8096" txt_name="ROCHESTER"><tr><td>A circle, 2 NM radius, centred at 512107N 0003010E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5028888889,51.3851566777,609.6 0.4974181135,51.3849800946,609.6 0.4920054548,51.3844522212,609.6 0.4867084083,51.383578665,609.6 0.4815832334,51.3823687051,609.6 0.4766843526,51.3808351933,609.6 0.4720637708,51.3789944163,609.6 0.4677705203,51.3768659223,609.6 0.4638501396,51.3744723119,609.6 0.4603441886,51.3718389969,609.6 0.4572898085,51.3689939296,609.6 0.4547193289,51.3659673044,609.6 0.4526599272,51.3627912369,609.6 0.4511333435,51.3594994211,609.6 0.4501556536,51.3561267721,609.6 0.4497371038,51.3527090546,609.6 0.4498820067,51.349282503,609.6 0.4505887009,51.3458834377,609.6 0.4518495739,51.3425478795,609.6 0.4536511481,51.3393111687,609.6 0.4559742282,51.336207591,609.6 0.4587941086,51.3332700152,609.6 0.4620808394,51.3305295459,609.6 0.4657995454,51.3280151953,609.6 0.4699107981,51.3257535772,609.6 0.4743710333,51.3237686269,609.6 0.4791330129,51.3220813485,609.6 0.4841463232,51.3207095942,609.6 0.4893579072,51.3196678763,609.6 0.4947126228,51.3189672149,609.6 0.5001538236,51.3186150215,609.6 0.5056239542,51.3186150215,609.6 0.511065155,51.3189672149,609.6 0.5164198706,51.3196678763,609.6 0.5216314546,51.3207095942,609.6 0.5266447649,51.3220813485,609.6 0.5314067444,51.3237686269,609.6 0.5358669797,51.3257535772,609.6 0.5399782323,51.3280151953,609.6 0.5436969384,51.3305295459,609.6 0.5469836691,51.3332700152,609.6 0.5498035496,51.336207591,609.6 0.5521266296,51.3393111687,609.6 0.5539282038,51.3425478795,609.6 0.5551890769,51.3458834377,609.6 0.5558957711,51.349282503,609.6 0.5560406739,51.3527090546,609.6 0.5556221241,51.3561267721,609.6 0.5546444343,51.3594994211,609.6 0.5531178505,51.3627912369,609.6 0.5510584489,51.3659673044,609.6 0.5484879693,51.3689939296,609.6 0.5454335892,51.3718389969,609.6 0.5419276382,51.3744723119,609.6 0.5380072574,51.3768659223,609.6 0.533714007,51.3789944163,609.6 0.5290934252,51.3808351933,609.6 0.5241945444,51.3823687051,609.6 0.5190693695,51.383578665,609.6 0.5137723229,51.3844522212,609.6 0.5083596643,51.3849800946,609.6 0.5028888889,51.3851566777,609.6 + + + + + + EGRU139B ROCHESTER RWY 02L + <table border="1" cellpadding="1" cellspacing="0" row_id="7776" txt_name="ROCHESTER RWY 02L"><tr><td>511821N 0002901E -<br/>511833N 0002812E -<br/>511920N 0002842E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to<br/>511909N 0002931E -<br/>511821N 0002901E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4834861111,51.3058194444,609.6 0.4918709444,51.3192941389,609.6 0.4872282527,51.320048953,609.6 0.4827129256,51.321062879,609.6 0.4783616944,51.3223276667,609.6 0.4701277778,51.3090888889,609.6 0.4834861111,51.3058194444,609.6 + + + + + + EGRU139C ROCHESTER RWY 20R + <table border="1" cellpadding="1" cellspacing="0" row_id="7968" txt_name="ROCHESTER RWY 20R"><tr><td>512359N 0003136E -<br/>512347N 0003224E -<br/>512250N 0003148E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to<br/>512302N 0003100E -<br/>512359N 0003136E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5266194444,51.3997527778,609.6 0.51678675,51.384,609.6 0.5213616864,51.3830840819,609.6 0.5257857541,51.381913545,609.6 0.5300228333,51.3804979444,609.6 0.5400055556,51.3964833333,609.6 0.5266194444,51.3997527778,609.6 + + + + + + EGRU139D ROCHESTER RWY 02R + <table border="1" cellpadding="1" cellspacing="0" row_id="8025" txt_name="ROCHESTER RWY 02R"><tr><td>511819N 0002902E -<br/>511831N 0002814E -<br/>511920N 0002844E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to<br/>511909N 0002933E -<br/>511819N 0002902E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4839722222,51.3053888889,609.6 0.4924984444,51.3192133056,609.6 0.4878400458,51.3199332926,609.6 0.4833041184,51.3209135101,609.6 0.4789275833,51.3221459722,609.6 0.4705972222,51.3086333333,609.6 0.4839722222,51.3053888889,609.6 + + + + + + EGRU139E ROCHESTER RWY 20L + <table border="1" cellpadding="1" cellspacing="0" row_id="7509" txt_name="ROCHESTER RWY 20L"><tr><td>512354N 0003134E -<br/>512342N 0003222E -<br/>512249N 0003149E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to<br/>512302N 0003102E -<br/>512354N 0003134E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5259916667,51.3983277778,609.6 0.5170946389,51.3839471944,609.6 0.5216613468,51.3830139545,609.6 0.5260746936,51.381826592,609.6 0.5302986389,51.3803948056,609.6 0.5393916667,51.3950861111,609.6 0.5259916667,51.3983277778,609.6 + + + + + + EGRU140A LASHENDEN/HEADCORN + <table border="1" cellpadding="1" cellspacing="0" row_id="8075" txt_name="LASHENDEN/HEADCORN"><tr><td>A circle, 2 NM radius, centred at 510923N 0003840E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6444444444,51.1896827956,609.6 0.6389968451,51.1895062075,609.6 0.6336071153,51.188978319,609.6 0.6283325063,51.1881047377,609.6 0.6232290383,51.1868947429,609.6 0.6183509028,51.1853611865,609.6 0.6137498838,51.1835203555,609.6 0.6094748059,51.1813917985,609.6 0.6055710142,51.1789981163,609.6 0.6020798931,51.1763647214,609.6 0.5990384267,51.1735195665,609.6 0.5964788084,51.1704928469,609.6 0.5944281011,51.1673166787,609.6 0.5929079536,51.164024757,609.6 0.591934375,51.1606519978,609.6 0.5915175691,51.1572341668,609.6 0.5916618315,51.1538074997,609.6 0.5923655089,51.150408318,609.6 0.5936210222,51.1470726439,609.6 0.5954149519,51.1438358191,609.6 0.5977281846,51.1407321305,609.6 0.6005361204,51.1377944485,609.6 0.6038089363,51.1350538788,609.6 0.6075119051,51.1325394351,609.6 0.6116057653,51.1302777326,609.6 0.6160471368,51.1282927074,609.6 0.6207889809,51.1266053649,609.6 0.6257810969,51.1252335582,609.6 0.6309706512,51.1241918004,609.6 0.6363027343,51.123491112,609.6 0.6417209384,51.123138905,609.6 0.6471679504,51.123138905,609.6 0.6525861545,51.123491112,609.6 0.6579182377,51.1241918004,609.6 0.663107792,51.1252335582,609.6 0.668099908,51.1266053649,609.6 0.6728417521,51.1282927074,609.6 0.6772831236,51.1302777326,609.6 0.6813769837,51.1325394351,609.6 0.6850799526,51.1350538788,609.6 0.6883527685,51.1377944485,609.6 0.6911607043,51.1407321305,609.6 0.693473937,51.1438358191,609.6 0.6952678667,51.1470726439,609.6 0.69652338,51.150408318,609.6 0.6972270574,51.1538074997,609.6 0.6973713198,51.1572341668,609.6 0.6969545139,51.1606519978,609.6 0.6959809353,51.164024757,609.6 0.6944607878,51.1673166787,609.6 0.6924100805,51.1704928469,609.6 0.6898504622,51.1735195665,609.6 0.6868089958,51.1763647214,609.6 0.6833178747,51.1789981163,609.6 0.679414083,51.1813917985,609.6 0.6751390051,51.1835203555,609.6 0.6705379861,51.1853611865,609.6 0.6656598506,51.1868947429,609.6 0.6605563826,51.1881047377,609.6 0.6552817736,51.188978319,609.6 0.6498920438,51.1895062075,609.6 0.6444444444,51.1896827956,609.6 + + + + + + EGRU140B LASHENDEN/HEADCORN RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7676" txt_name="LASHENDEN/HEADCORN RWY 10"><tr><td>510953N 0003359E -<br/>511024N 0003412E -<br/>511009N 0003544E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to<br/>510937N 0003531E -<br/>510953N 0003359E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5663138889,51.1645833333,609.6 0.5918729444,51.1603403333,609.6 0.5926518716,51.1633046336,609.6 0.5938527671,51.1662126983,609.6 0.5954659167,51.1690408333,609.6 0.5699777778,51.1732722222,609.6 0.5663138889,51.1645833333,609.6 + + + + + + EGRU140C LASHENDEN/HEADCORN RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="8105" txt_name="LASHENDEN/HEADCORN RWY 28"><tr><td>510853N 0004319E -<br/>510821N 0004306E -<br/>510836N 0004136E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to<br/>510908N 0004149E -<br/>510853N 0004319E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.7218944444,51.1479583333,609.6 0.6969505833,51.1521301944,609.6 0.6961247654,51.1491710648,609.6 0.6948783343,51.1462707894,609.6 0.6932215,51.1434529722,609.6 0.7182361111,51.1392694444,609.6 0.7218944444,51.1479583333,609.6 + + + + + + EGRU141A EARLS COLNE + <table border="1" cellpadding="1" cellspacing="0" row_id="7792" txt_name="EARLS COLNE"><tr><td>A circle, 2 NM radius, centred at 515452N 0004057E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6825,51.9477340257,609.6 0.6769610427,51.947557457,609.6 0.6714809291,51.9470296268,609.6 0.6661178735,51.9461561423,609.6 0.6609288387,51.9449462823,609.6 0.6559689273,51.943412898,609.6 0.6512907936,51.9415722755,609.6 0.6469440818,51.9394439619,609.6 0.6429748979,51.9370505568,609.6 0.6394253193,51.9344174707,609.6 0.636332949,51.9315726541,609.6 0.6337305176,51.9285462996,609.6 0.631645539,51.9253705205,609.6 0.6301000212,51.9220790084,609.6 0.6291102374,51.9187066755,609.6 0.6286865582,51.9152892834,609.6 0.6288333463,51.9118630633,609.6 0.6295489163,51.908464332,609.6 0.6308255577,51.9051291065,609.6 0.632649622,51.9018927233,609.6 0.635001672,51.8987894642,609.6 0.6378566928,51.8958521937,609.6 0.6411843597,51.8931120127,609.6 0.6449493626,51.8905979296,609.6 0.6491117818,51.8883365545,609.6 0.6536275115,51.8863518193,609.6 0.6584487265,51.8846647251,609.6 0.6635243874,51.8832931215,609.6 0.668800779,51.8822515187,609.6 0.6742220758,51.8815509349,609.6 0.6797309292,51.8811987806,609.6 0.6852690708,51.8811987806,609.6 0.6907779242,51.8815509349,609.6 0.696199221,51.8822515187,609.6 0.7014756126,51.8832931215,609.6 0.7065512735,51.8846647251,609.6 0.7113724885,51.8863518193,609.6 0.7158882182,51.8883365545,609.6 0.7200506374,51.8905979296,609.6 0.7238156403,51.8931120127,609.6 0.7271433072,51.8958521937,609.6 0.729998328,51.8987894642,609.6 0.732350378,51.9018927233,609.6 0.7341744423,51.9051291065,609.6 0.7354510837,51.908464332,609.6 0.7361666537,51.9118630633,609.6 0.7363134418,51.9152892834,609.6 0.7358897626,51.9187066755,609.6 0.7348999788,51.9220790084,609.6 0.733354461,51.9253705205,609.6 0.7312694824,51.9285462996,609.6 0.728667051,51.9315726541,609.6 0.7255746807,51.9344174707,609.6 0.7220251021,51.9370505568,609.6 0.7180559182,51.9394439619,609.6 0.7137092064,51.9415722755,609.6 0.7090310727,51.943412898,609.6 0.7040711613,51.9449462823,609.6 0.6988821265,51.9461561423,609.6 0.6935190709,51.9470296268,609.6 0.6880389573,51.947557457,609.6 0.6825,51.9477340257,609.6 + + + + + + EGRU141B EARLS COLNE RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7746" txt_name="EARLS COLNE RWY 06"><tr><td>515309N 0003708E -<br/>515337N 0003642E -<br/>515405N 0003759E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to<br/>515337N 0003826E -<br/>515309N 0003708E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6188194444,51.8858888889,609.6 0.6405008056,51.8936288333,609.6 0.6376370069,51.8960555344,609.6 0.6351382452,51.8986320512,609.6 0.6330249167,51.9013374167,609.6 0.6115694444,51.8936777778,609.6 0.6188194444,51.8858888889,609.6 + + + + + + EGRU141C EARLS COLNE RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7902" txt_name="EARLS COLNE RWY 24"><tr><td>515631N 0004450E -<br/>515603N 0004516E -<br/>515535N 0004358E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to<br/>515604N 0004332E -<br/>515631N 0004450E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.7473027778,51.942025,609.6 0.7256713333,51.9343375,609.6 0.7283957123,51.9318493242,609.6 0.7307458014,51.9292193892,609.6 0.7327025,51.9264691389,609.6 0.7545583333,51.9342361111,609.6 0.7473027778,51.942025,609.6 + + + + + + EGRU142A SOUTHEND + <table border="1" cellpadding="1" cellspacing="0" row_id="7552" txt_name="SOUTHEND"><tr><td>A circle, 2.5 NM radius, centred at 513413N 0004136E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6933333333,51.6118921753,609.6 0.6871661804,51.6117144943,609.6 0.6810517867,51.6111829714,609.6 0.6750424567,51.6103021536,609.6 0.6691895887,51.6090795755,609.6 0.6635432321,51.6075256945,609.6 0.6581516565,51.6056538008,609.6 0.6530609364,51.6034799024,609.6 0.648314556,51.6010225879,609.6 0.6439530358,51.5983028658,609.6 0.6400135864,51.5953439844,609.6 0.6365297913,51.5921712314,609.6 0.6335313205,51.5888117171,609.6 0.63104368,51.5852941413,609.6 0.6290879964,51.5816485477,609.6 0.62768084,51.5779060657,609.6 0.6268340873,51.5740986447,609.6 0.6265548244,51.5702587803,609.6 0.6268452906,51.5664192368,609.6 0.627702865,51.5626127676,609.6 0.6291200932,51.5588718361,609.6 0.6310847554,51.5552283386,609.6 0.6335799758,51.5517133334,609.6 0.6365843696,51.5483567765,609.6 0.6400722293,51.5451872669,609.6 0.644013746,51.5422318046,609.6 0.6483752663,51.5395155609,609.6 0.6531195793,51.5370616655,609.6 0.6582062349,51.5348910106,609.6 0.6635918876,51.5330220742,609.6 0.6692306642,51.5314707638,609.6 0.6750745535,51.5302502819,609.6 0.6810738118,51.5293710145,609.6 0.6871773836,51.5288404435,609.6 0.6933333333,51.5286630835,609.6 0.699489283,51.5288404435,609.6 0.7055928549,51.5293710145,609.6 0.7115921131,51.5302502819,609.6 0.7174360024,51.5314707638,609.6 0.7230747791,51.5330220742,609.6 0.7284604317,51.5348910106,609.6 0.7335470874,51.5370616655,609.6 0.7382914004,51.5395155609,609.6 0.7426529206,51.5422318046,609.6 0.7465944374,51.5451872669,609.6 0.750082297,51.5483567765,609.6 0.7530866908,51.5517133334,609.6 0.7555819112,51.5552283386,609.6 0.7575465735,51.5588718361,609.6 0.7589638016,51.5626127676,609.6 0.7598213761,51.5664192368,609.6 0.7601118423,51.5702587803,609.6 0.7598325793,51.5740986447,609.6 0.7589858267,51.5779060657,609.6 0.7575786702,51.5816485477,609.6 0.7556229866,51.5852941413,609.6 0.7531353462,51.5888117171,609.6 0.7501368754,51.5921712314,609.6 0.7466530802,51.5953439844,609.6 0.7427136309,51.5983028658,609.6 0.7383521107,51.6010225879,609.6 0.7336057302,51.6034799024,609.6 0.7285150102,51.6056538008,609.6 0.7231234345,51.6075256945,609.6 0.7174770779,51.6090795755,609.6 0.7116242099,51.6103021536,609.6 0.7056148799,51.6111829714,609.6 0.6995004863,51.6117144943,609.6 0.6933333333,51.6118921753,609.6 + + + + + + EGRU142B SOUTHEND RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8092" txt_name="SOUTHEND RWY 05"><tr><td>513209N 0003745E -<br/>513236N 0003714E -<br/>513259N 0003807E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to<br/>513233N 0003837E -<br/>513209N 0003745E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6291166667,51.5359555556,609.6 0.6436260556,51.5424989444,609.6 0.6405434667,51.544803412,609.6 0.637734927,51.5472403342,609.6 0.6352150556,51.5497970556,609.6 0.6206805556,51.5432416667,609.6 0.6291166667,51.5359555556,609.6 + + + + + + EGRU142C SOUTHEND RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7541" txt_name="SOUTHEND RWY 23"><tr><td>513615N 0004523E -<br/>513549N 0004553E -<br/>513527N 0004505E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to<br/>513554N 0004434E -<br/>513615N 0004523E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.7563638889,51.6042944444,609.6 0.7428335,51.5982206389,609.6 0.7459369184,51.5959248333,609.6 0.7487662855,51.5934956228,609.6 0.7513069167,51.5909456667,609.6 0.7648138889,51.5970083333,609.6 0.7563638889,51.6042944444,609.6 + + + + + + EGRU143A LONDON HELIPORT + <table border="1" cellpadding="1" cellspacing="0" row_id="7694" txt_name="LONDON HELIPORT"><tr><td>A circle, 2 NM radius, centred at 512812N 0001046W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1795388889,51.50322267,609.6 -0.1850237897,51.5030460899,609.6 -0.1904504231,51.5025182256,609.6 -0.1957611449,51.5016446845,609.6 -0.2008995498,51.5004347457,609.6 -0.2058110744,51.4989012607,609.6 -0.2104435795,51.4970605163,609.6 -0.2147479056,51.4949320603,609.6 -0.2186783971,51.4925384931,609.6 -0.2221933866,51.4899052263,609.6 -0.2252556374,51.4870602117,609.6 -0.2278327366,51.4840336435,609.6 -0.2298974372,51.4808576366,609.6 -0.2314279437,51.4775658847,609.6 -0.2324081392,51.4741933023,609.6 -0.2328277518,51.4707756531,609.6 -0.2326824584,51.4673491713,609.6 -0.2319739255,51.4639501761,609.6 -0.2307097858,51.4606146879,609.6 -0.2289035523,51.4573780459,609.6 -0.2265744705,51.4542745352,609.6 -0.22374731,51.4513370235,609.6 -0.2204520984,51.4485966148,609.6 -0.2167238008,51.4460823203,609.6 -0.2126019478,51.4438207533,609.6 -0.2081302155,51.4418358481,609.6 -0.2033559639,51.4401486084,609.6 -0.1983297361,51.4387768857,609.6 -0.1931047256,51.437735192,609.6 -0.187736216,51.4370345469,609.6 -0.1822809993,51.4366823617,609.6 -0.1767967785,51.4366823617,609.6 -0.1713415617,51.4370345469,609.6 -0.1659730521,51.437735192,609.6 -0.1607480417,51.4387768857,609.6 -0.1557218139,51.4401486084,609.6 -0.1509475623,51.4418358481,609.6 -0.14647583,51.4438207533,609.6 -0.142353977,51.4460823203,609.6 -0.1386256794,51.4485966148,609.6 -0.1353304678,51.4513370235,609.6 -0.1325033072,51.4542745352,609.6 -0.1301742255,51.4573780459,609.6 -0.128367992,51.4606146879,609.6 -0.1271038523,51.4639501761,609.6 -0.1263953194,51.4673491713,609.6 -0.126250026,51.4707756531,609.6 -0.1266696386,51.4741933023,609.6 -0.1276498341,51.4775658847,609.6 -0.1291803406,51.4808576366,609.6 -0.1312450412,51.4840336435,609.6 -0.1338221404,51.4870602117,609.6 -0.1368843911,51.4899052263,609.6 -0.1403993807,51.4925384931,609.6 -0.1443298721,51.4949320603,609.6 -0.1486341983,51.4970605163,609.6 -0.1532667033,51.4989012607,609.6 -0.158178228,51.5004347457,609.6 -0.1633166329,51.5016446845,609.6 -0.1686273547,51.5025182256,609.6 -0.1740539881,51.5030460899,609.6 -0.1795388889,51.50322267,609.6 + + + + + + EGRU145A KENLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="8505" txt_name="KENLEY"><tr><td>A circle, 2 NM radius, centred at 511821N 0000536W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0934361111,51.3392541623,609.6 -0.0989014207,51.339077578,609.6 -0.1043086718,51.3385497011,609.6 -0.1096004267,51.337676139,609.6 -0.1147204823,51.3364661709,609.6 -0.1196144705,51.3349326486,609.6 -0.1242304386,51.333091859,609.6 -0.1285194033,51.3309633502,609.6 -0.1324358716,51.3285697229,609.6 -0.1359383252,51.3259363892,609.6 -0.1389896597,51.3230913013,609.6 -0.1415575778,51.320064654,609.6 -0.143614929,51.3168885628,609.6 -0.1451399949,51.3135967222,609.6 -0.1461167151,51.3102240474,609.6 -0.1465348537,51.3068063032,609.6 -0.1463901019,51.3033797245,609.6 -0.1456841192,51.2999806319,609.6 -0.1444245102,51.2966450465,609.6 -0.1426247389,51.2934083089,609.6 -0.1403039812,51.2903047052,609.6 -0.1374869178,51.2873671045,609.6 -0.1342034687,51.2846266116,609.6 -0.1304884741,51.2821122391,609.6 -0.1263813233,51.2798506013,609.6 -0.1219255368,51.2778656334,609.6 -0.117168306,51.2761783399,609.6 -0.1121599941,51.2748065733,609.6 -0.1069536056,51.273764846,609.6 -0.1016042276,51.2730641783,609.6 -0.0961684503,51.2727119817,609.6 -0.090703772,51.2727119817,609.6 -0.0852679946,51.2730641783,609.6 -0.0799186166,51.273764846,609.6 -0.0747122281,51.2748065733,609.6 -0.0697039163,51.2761783399,609.6 -0.0649466854,51.2778656334,609.6 -0.060490899,51.2798506013,609.6 -0.0563837481,51.2821122391,609.6 -0.0526687535,51.2846266116,609.6 -0.0493853045,51.2873671045,609.6 -0.046568241,51.2903047052,609.6 -0.0442474834,51.2934083089,609.6 -0.0424477121,51.2966450465,609.6 -0.0411881031,51.2999806319,609.6 -0.0404821204,51.3033797245,609.6 -0.0403373686,51.3068063032,609.6 -0.0407555071,51.3102240474,609.6 -0.0417322274,51.3135967222,609.6 -0.0432572932,51.3168885628,609.6 -0.0453146444,51.320064654,609.6 -0.0478825625,51.3230913013,609.6 -0.050933897,51.3259363892,609.6 -0.0544363506,51.3285697229,609.6 -0.058352819,51.3309633502,609.6 -0.0626417836,51.333091859,609.6 -0.0672577518,51.3349326486,609.6 -0.07215174,51.3364661709,609.6 -0.0772717955,51.337676139,609.6 -0.0825635504,51.3385497011,609.6 -0.0879708015,51.339077578,609.6 -0.0934361111,51.3392541623,609.6 + + + + + + EGRU146A UPAVON + <table border="1" cellpadding="1" cellspacing="0" row_id="8503" txt_name="UPAVON"><tr><td>A circle, 2 NM radius, centred at 511710N 0014652W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7810361111,51.3194987197,609.6 -1.7864990728,51.3193221349,609.6 -1.791904001,51.3187942564,609.6 -1.7971934828,51.3179206918,609.6 -1.8023113392,51.3167107202,609.6 -1.8072032258,51.3151771934,609.6 -1.8118172121,51.3133363983,609.6 -1.8161043357,51.3112078832,609.6 -1.8200191235,51.3088142487,609.6 -1.8235200746,51.3061809068,609.6 -1.8265701009,51.3033358101,609.6 -1.8291369187,51.3003091533,609.6 -1.8311933891,51.2971330519,609.6 -1.8327178029,51.2938412006,609.6 -1.8336941066,51.2904685147,609.6 -1.8341120685,51.287050759,609.6 -1.8339673816,51.2836241687,609.6 -1.8332617045,51.2802250642,609.6 -1.8320026385,51.2768894671,609.6 -1.8302036416,51.2736527181,609.6 -1.8278838816,51.2705491032,609.6 -1.8250680283,51.2676114917,609.6 -1.8217859889,51.2648709887,609.6 -1.8180725886,51.2623566068,609.6 -1.8139671997,51.2600949604,609.6 -1.8095133244,51.2581099849,609.6 -1.8047581334,51.256422685,609.6 -1.7997519687,51.255050913,609.6 -1.7945478119,51.2540091818,609.6 -1.7892007268,51.2533085113,609.6 -1.7837672792,51.2529563133,609.6 -1.778304943,51.2529563133,609.6 -1.7728714954,51.2533085113,609.6 -1.7675244103,51.2540091818,609.6 -1.7623202535,51.255050913,609.6 -1.7573140888,51.256422685,609.6 -1.7525588979,51.2581099849,609.6 -1.7481050225,51.2600949604,609.6 -1.7439996337,51.2623566068,609.6 -1.7402862334,51.2648709887,609.6 -1.737004194,51.2676114917,609.6 -1.7341883406,51.2705491032,609.6 -1.7318685806,51.2736527181,609.6 -1.7300695837,51.2768894671,609.6 -1.7288105177,51.2802250642,609.6 -1.7281048407,51.2836241687,609.6 -1.7279601537,51.287050759,609.6 -1.7283781156,51.2904685147,609.6 -1.7293544194,51.2938412006,609.6 -1.7308788332,51.2971330519,609.6 -1.7329353036,51.3003091533,609.6 -1.7355021213,51.3033358101,609.6 -1.7385521476,51.3061809068,609.6 -1.7420530988,51.3088142487,609.6 -1.7459678865,51.3112078832,609.6 -1.7502550102,51.3133363983,609.6 -1.7548689964,51.3151771934,609.6 -1.759760883,51.3167107202,609.6 -1.7648787395,51.3179206918,609.6 -1.7701682212,51.3187942564,609.6 -1.7755731495,51.3193221349,609.6 -1.7810361111,51.3194987197,609.6 + + + + + + EGRU147A WESTON ON THE GREEN + <table border="1" cellpadding="1" cellspacing="0" row_id="8502" txt_name="WESTON ON THE GREEN"><tr><td>A circle, 2 NM radius, centred at 515245N 0011304W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.217775,51.9124147822,609.6 -1.2233096109,51.9122382126,609.6 -1.2287854244,51.9117103797,609.6 -1.2341442722,51.9108368907,609.6 -1.2393292361,51.9096270245,609.6 -1.2442852569,51.9080936322,609.6 -1.2489597219,51.906253,609.6 -1.2533030257,51.9041246752,609.6 -1.2572690985,51.9017312573,609.6 -1.260815896,51.8990981568,609.6 -1.2639058446,51.8962533245,609.6 -1.2665062392,51.8932269531,609.6 -1.2685895874,51.8900511559,609.6 -1.2701338983,51.8867596248,609.6 -1.2711229111,51.8833872721,609.6 -1.2715462634,51.8799698596,609.6 -1.2713995955,51.8765436188,609.6 -1.2706845913,51.8731448665,609.6 -1.2694089551,51.8698096202,609.6 -1.2675863246,51.8665732165,609.6 -1.2652361213,51.8634699373,609.6 -1.2623833407,51.8605326478,609.6 -1.2590582833,51.8577924487,609.6 -1.2552962317,51.8552783487,609.6 -1.2511370741,51.8530169585,609.6 -1.246624882,51.8510322098,609.6 -1.2418074431,51.849345104,609.6 -1.2367357568,51.8479734909,609.6 -1.2314634964,51.8469318809,609.6 -1.2260464439,51.8462312922,609.6 -1.2205419031,51.8458791355,609.6 -1.2150080969,51.8458791355,609.6 -1.2095035561,51.8462312922,609.6 -1.2040865036,51.8469318809,609.6 -1.1988142432,51.8479734909,609.6 -1.1937425569,51.849345104,609.6 -1.188925118,51.8510322098,609.6 -1.1844129259,51.8530169585,609.6 -1.1802537683,51.8552783487,609.6 -1.1764917167,51.8577924487,609.6 -1.1731666593,51.8605326478,609.6 -1.1703138787,51.8634699373,609.6 -1.1679636754,51.8665732165,609.6 -1.1661410449,51.8698096202,609.6 -1.1648654087,51.8731448665,609.6 -1.1641504045,51.8765436188,609.6 -1.1640037366,51.8799698596,609.6 -1.1644270889,51.8833872721,609.6 -1.1654161017,51.8867596248,609.6 -1.1669604126,51.8900511559,609.6 -1.1690437608,51.8932269531,609.6 -1.1716441554,51.8962533245,609.6 -1.174734104,51.8990981568,609.6 -1.1782809015,51.9017312573,609.6 -1.1822469743,51.9041246752,609.6 -1.1865902781,51.906253,609.6 -1.1912647431,51.9080936322,609.6 -1.1962207639,51.9096270245,609.6 -1.2014057278,51.9108368907,609.6 -1.2067645756,51.9117103797,609.6 -1.2122403891,51.9122382126,609.6 -1.217775,51.9124147822,609.6 + + + + + + EGRU148A LITTLE RISSINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="8844" txt_name="LITTLE RISSINGTON"><tr><td>A circle, 2 NM radius, centred at 515202N 0014139W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6941888889,51.9003787396,609.6 -1.6997220206,51.9002021697,609.6 -1.7051963708,51.8996743359,609.6 -1.7105537866,51.8988008453,609.6 -1.7157373652,51.897590977,609.6 -1.720692062,51.8960575819,609.6 -1.7253652785,51.8942169465,609.6 -1.7297074225,51.8920886178,609.6 -1.7336724366,51.8896951955,609.6 -1.7372182877,51.8870620902,609.6 -1.7403074122,51.8842172525,609.6 -1.7429071136,51.8811908754,609.6 -1.744989907,51.878015072,609.6 -1.7465338071,51.8747235344,609.6 -1.7475225576,51.871351175,609.6 -1.7479457987,51.8679337555,609.6 -1.7477991716,51.8645075076,609.6 -1.74708436,51.8611087482,609.6 -1.7458090659,51.8577734948,609.6 -1.7439869233,51.8545370841,609.6 -1.7416373485,51.8514337981,609.6 -1.7387853301,51.848496502,609.6 -1.7354611608,51.8457562968,609.6 -1.7317001135,51.8432421911,609.6 -1.7275420659,51.8409807957,609.6 -1.7230310777,51.8389960424,609.6 -1.7182149238,51.8373089327,609.6 -1.7131445901,51.8359373164,609.6 -1.7078737356,51.8348957039,609.6 -1.7024581275,51.8341951135,609.6 -1.6969550543,51.8338429559,609.6 -1.6914227235,51.8338429559,609.6 -1.6859196503,51.8341951135,609.6 -1.6805040421,51.8348957039,609.6 -1.6752331877,51.8359373164,609.6 -1.670162854,51.8373089327,609.6 -1.6653467001,51.8389960424,609.6 -1.6608357118,51.8409807957,609.6 -1.6566776643,51.8432421911,609.6 -1.6529166169,51.8457562968,609.6 -1.6495924477,51.848496502,609.6 -1.6467404293,51.8514337981,609.6 -1.6443908545,51.8545370841,609.6 -1.6425687119,51.8577734948,609.6 -1.6412934178,51.8611087482,609.6 -1.6405786061,51.8645075076,609.6 -1.6404319791,51.8679337555,609.6 -1.6408552202,51.871351175,609.6 -1.6418439707,51.8747235344,609.6 -1.6433878708,51.878015072,609.6 -1.6454706642,51.8811908754,609.6 -1.6480703656,51.8842172525,609.6 -1.6511594901,51.8870620902,609.6 -1.6547053411,51.8896951955,609.6 -1.6586703553,51.8920886178,609.6 -1.6630124993,51.8942169465,609.6 -1.6676857158,51.8960575819,609.6 -1.6726404126,51.897590977,609.6 -1.6778239912,51.8988008453,609.6 -1.6831814069,51.8996743359,609.6 -1.6886557571,51.9002021697,609.6 -1.6941888889,51.9003787396,609.6 + + + + + + EGRU148B LITTLE RISSINGTON RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="8842" txt_name="LITTLE RISSINGTON RWY 04"><tr><td>514928N 0014421W -<br/>514948N 0014502W -<br/>515038N 0014358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515018N 0014317W -<br/>514928N 0014421W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7391218333,51.8243148333,609.6 -1.7213525556,51.8383616389,609.6 -1.7254230493,51.8399944628,609.6 -1.7292396587,51.8418478204,609.6 -1.7327713333,51.8439066389,609.6 -1.7505336944,51.8298625,609.6 -1.7391218333,51.8243148333,609.6 + + + + + + EGRU148C LITTLE RISSINGTON RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="8841" txt_name="LITTLE RISSINGTON RWY 22"><tr><td>515435N 0013857W -<br/>515415N 0013816W -<br/>515325N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515345N 0014001W -<br/>515435N 0013857W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6491845278,51.9098425278,609.6 -1.6669975556,51.89581225,609.6 -1.6629237494,51.8941777929,609.6 -1.6591049889,51.8923226558,609.6 -1.6555723889,51.8902619722,609.6 -1.6377523889,51.9042949167,609.6 -1.6491845278,51.9098425278,609.6 + + + + + + EGRU148D LITTLE RISSINGTON RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8846" txt_name="LITTLE RISSINGTON RWY 09"><tr><td>515133N 0014621W -<br/>515205N 0014626W -<br/>515210N 0014452W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515138N 0014449W -<br/>515133N 0014621W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7725545278,51.8591138056,609.6 -1.7468936389,51.8604959167,609.6 -1.7476408861,51.8634648455,609.6 -1.7479527579,51.8664633953,609.6 -1.7478266389,51.8694671389,609.6 -1.7737993056,51.8680682778,609.6 -1.7725545278,51.8591138056,609.6 + + + + + + EGRU148E LITTLE RISSINGTON RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="8845" txt_name="LITTLE RISSINGTON RWY 27"><tr><td>515236N 0013649W -<br/>515204N 0013645W -<br/>515158N 0013826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515230N 0013831W -<br/>515236N 0013649W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6136181389,51.8766028056,609.6 -1.6419936111,51.8751070833,609.6 -1.641039975,51.8721608815,609.6 -1.6405194626,51.869173453,609.6 -1.64043625,51.8661691389,609.6 -1.6123731111,51.8676483611,609.6 -1.6136181389,51.8766028056,609.6 + + + + + + EGRU148F LITTLE RISSINGTON RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="8843" txt_name="LITTLE RISSINGTON RWY 13"><tr><td>515336N 0014536W -<br/>515400N 0014501W -<br/>515326N 0014357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515300N 0014429W -<br/>515336N 0014536W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7599274722,51.8932725278,609.6 -1.7412547778,51.8831991667,609.6 -1.738709554,51.8857675435,609.6 -1.735799195,51.8881829232,609.6 -1.7325475278,51.8904255,609.6 -1.7503725833,51.9000425,609.6 -1.7599274722,51.8932725278,609.6 + + + + + + EGRU148G LITTLE RISSINGTON RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="8847" txt_name="LITTLE RISSINGTON RWY 31"><tr><td>515008N 0013751W -<br/>514943N 0013825W -<br/>515025N 0013943W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to<br/>515048N 0013906W -<br/>515008N 0013751W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6308653333,51.8354350556,609.6 -1.6516788333,51.84670925,609.6 -1.6548287542,51.8444133462,609.6 -1.6583005968,51.8423031413,609.6 -1.6620659167,51.8403958889,609.6 -1.6404065278,51.8286650278,609.6 -1.6308653333,51.8354350556,609.6 + + + + + + EGRU149 HMP ASHFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="14148" txt_name="HMP ASHFIELD"><tr><td>512911N 0022623W -<br/>512908N 0022602W -<br/>512901N 0022556W -<br/>512852N 0022556W -<br/>512843N 0022602W -<br/>512836N 0022619W -<br/>512841N 0022644W -<br/>512854N 0022652W -<br/>512907N 0022641W -<br/>512911N 0022623W <br/>Upper limit: 900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 405 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4396638889,51.4865194444,274.32 -2.4446388889,51.485325,274.32 -2.4478944444,51.4817361111,274.32 -2.4456416667,51.4779722222,274.32 -2.438575,51.4765722222,274.32 -2.4337638889,51.4785194444,274.32 -2.4321583333,51.4811166667,274.32 -2.4321638889,51.4834777778,274.32 -2.4338861111,51.4854361111,274.32 -2.4396638889,51.4865194444,274.32 + + + + + + EGRU150 HMP AYLESBURY + <table border="1" cellpadding="1" cellspacing="0" row_id="14143" txt_name="HMP AYLESBURY"><tr><td>514938N 0004807W -<br/>514935N 0004742W -<br/>514916N 0004724W -<br/>514904N 0004732W -<br/>514857N 0004807W -<br/>514914N 0004830W -<br/>514926N 0004829W -<br/>514938N 0004807W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 311 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8018638889,51.8272222222,243.84 -0.8080638889,51.8240194444,243.84 -0.8083861111,51.8205972222,243.84 -0.8018833333,51.8157416667,243.84 -0.7922305556,51.8176833333,243.84 -0.7900166667,51.8210444444,243.84 -0.7949638889,51.8265,243.84 -0.8018638889,51.8272222222,243.84 + + + + + + EGRU151 HMP BELMARSH/THAMESIDE/ISIS + <table border="1" cellpadding="1" cellspacing="0" row_id="14128" txt_name="HMP BELMARSH/THAMESIDE/ISIS"><tr><td>513012N 0000557E -<br/>512942N 0000624E -<br/>512930N 0000550E -<br/>512918N 0000540E -<br/>512927N 0000450E -<br/>512952N 0000501E -<br/>513012N 0000557E <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.<br/>NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 16 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0990305556,51.5032916667,152.4 0.0834944444,51.4976583333,152.4 0.0804333333,51.4909166667,152.4 0.0945611111,51.4882305556,152.4 0.097125,51.4915305556,152.4 0.1065527778,51.4949638889,152.4 0.0990305556,51.5032916667,152.4 + + + + + + EGRU152 HMP BRISTOL + <table border="1" cellpadding="1" cellspacing="0" row_id="14084" txt_name="HMP BRISTOL"><tr><td>512909N 0023540W -<br/>512905N 0023520W -<br/>512857N 0023505W -<br/>512849N 0023503W -<br/>512837N 0023512W -<br/>512834N 0023540W -<br/>512848N 0023602W -<br/>512901N 0023600W -<br/>512909N 0023540W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 206 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5945583333,51.4857444444,213.36 -2.5999805556,51.4835722222,213.36 -2.6006527778,51.4800527778,213.36 -2.5943277778,51.4762111111,213.36 -2.5866972222,51.4770777778,213.36 -2.5841138889,51.4802305556,213.36 -2.5845861111,51.4824888889,213.36 -2.5889111111,51.4847722222,213.36 -2.5945583333,51.4857444444,213.36 + + + + + + EGRU153 HMP BRIXTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14156" txt_name="HMP BRIXTON"><tr><td>512722N 0000738W -<br/>512718N 0000710W -<br/>512709N 0000703W -<br/>512656N 0000707W -<br/>512650N 0000721W -<br/>512653N 0000755W -<br/>512714N 0000758W -<br/>512722N 0000738W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.<br/>London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 125 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1273222222,51.4562194444,182.88 -0.132775,51.4538527778,182.88 -0.132025,51.4481638889,182.88 -0.1223611111,51.4472388889,182.88 -0.1186333333,51.4488194444,182.88 -0.1174055556,51.4525472222,182.88 -0.1195583333,51.4551111111,182.88 -0.1273222222,51.4562194444,182.88 + + + + + + EGRU154 HMP BRONZEFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="14083" txt_name="HMP BRONZEFIELD"><tr><td>512610N 0002935W -<br/>512618N 0002841W -<br/>512554N 0002832W -<br/>512544N 0002845W -<br/>512541N 0002907W -<br/>512549N 0002925W -<br/>512610N 0002935W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.<br/>NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 53 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4930166667,51.4362277778,152.4 -0.4903944444,51.4301416667,152.4 -0.4851722222,51.4280722222,152.4 -0.4792944444,51.4289388889,152.4 -0.4755583333,51.4316027778,152.4 -0.4780916667,51.4384027778,152.4 -0.4930166667,51.4362277778,152.4 + + + + + + EGRU155 HMP BULLINGDON + <table border="1" cellpadding="1" cellspacing="0" row_id="14134" txt_name="HMP BULLINGDON"><tr><td>515113N 0010603W -<br/>515114N 0010521W -<br/>515103N 0010505W -<br/>515049N 0010507W -<br/>515037N 0010526W -<br/>515038N 0010553W -<br/>515050N 0010610W -<br/>515113N 0010603W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 267 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1007305556,51.8536888889,213.36 -1.1028972222,51.8471805556,213.36 -1.0980777778,51.84375,213.36 -1.0904388889,51.8436166667,213.36 -1.0851861111,51.8468194444,213.36 -1.0848166667,51.8508305556,213.36 -1.0891916667,51.8538083333,213.36 -1.1007305556,51.8536888889,213.36 + + + + + + EGRU156 HMP CARDIFF + <table border="1" cellpadding="1" cellspacing="0" row_id="14091" txt_name="HMP CARDIFF"><tr><td>512910N 0031002W -<br/>512854N 0030934W -<br/>512834N 0030952W -<br/>512831N 0031011W -<br/>512844N 0031031W -<br/>512902N 0031033W -<br/>512910N 0031002W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 39 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1672138889,51.4860472222,152.4 -3.1757305556,51.4838527778,152.4 -3.1752527778,51.4788194444,152.4 -3.1696805556,51.475225,152.4 -3.1643611111,51.4761972222,152.4 -3.1593388889,51.4816305556,152.4 -3.1672138889,51.4860472222,152.4 + + + + + + EGRU157 HMP CHELMSFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14137" txt_name="HMP CHELMSFORD"><tr><td>514431N 0002858E -<br/>514416N 0002945E -<br/>514359N 0002948E -<br/>514351N 0002936E -<br/>514352N 0002909E -<br/>514404N 0002833E -<br/>514431N 0002858E <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 135 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4828416667,51.7420111111,182.88 0.4758444444,51.7345722222,182.88 0.4857611111,51.7312444444,182.88 0.4934583333,51.7308777778,182.88 0.4965583333,51.7330944444,182.88 0.4958222222,51.7377777778,182.88 0.4828416667,51.7420111111,182.88 + + + + + + EGRU158 HMP COLDINGLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14069" txt_name="HMP COLDINGLEY"><tr><td>511938N 0003849W -<br/>511937N 0003818W -<br/>511917N 0003756W -<br/>511858N 0003841W -<br/>511917N 0003910W -<br/>511938N 0003849W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 174 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6469388889,51.3271333333,182.88 -0.6526472222,51.3213472222,182.88 -0.6445972222,51.3159916667,182.88 -0.6323444444,51.3213555556,182.88 -0.6382083333,51.3268527778,182.88 -0.6469388889,51.3271333333,182.88 + + + + + + EGRU159 HMP DOWNVIEW/HIGH DOWN + <table border="1" cellpadding="1" cellspacing="0" row_id="14090" txt_name="HMP DOWNVIEW/HIGH DOWN"><tr><td>512036N 0001131W -<br/>512039N 0001059W -<br/>512019N 0001050W -<br/>511952N 0001055W -<br/>511948N 0001137W -<br/>511959N 0001154W -<br/>512027N 0001150W -<br/>512036N 0001131W <br/>Upper limit: 900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 457 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1918888889,51.34335,274.32 -0.1973305556,51.3409,274.32 -0.1983277778,51.3329555556,274.32 -0.1936833333,51.3300944444,274.32 -0.1818777778,51.3310472222,274.32 -0.1805555556,51.3386166667,274.32 -0.1830305556,51.3442861111,274.32 -0.1918888889,51.34335,274.32 + + + + + + EGRU160 HMP EAST SUTTON PARK + <table border="1" cellpadding="1" cellspacing="0" row_id="14062" txt_name="HMP EAST SUTTON PARK"><tr><td>511311N 0003654E -<br/>511313N 0003731E -<br/>511249N 0003733E -<br/>511235N 0003642E -<br/>511301N 0003632E -<br/>511311N 0003654E <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 376 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6149277778,51.2196083333,243.84 0.6088027778,51.2168722222,243.84 0.6115416667,51.2098166667,243.84 0.6257305556,51.213475,243.84 0.6254055556,51.2202638889,243.84 0.6149277778,51.2196083333,243.84 + + + + + + EGRU161 HMP EASTWOOD PARK + <table border="1" cellpadding="1" cellspacing="0" row_id="14093" txt_name="HMP EASTWOOD PARK"><tr><td>513819N 0022840W -<br/>513823N 0022800W -<br/>513822N 0022740W -<br/>513803N 0022723W -<br/>513751N 0022754W -<br/>513747N 0022829W -<br/>513819N 0022840W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 117 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4776472222,51.6386305556,182.88 -2.4745916667,51.6297,182.88 -2.4648611111,51.6309111111,182.88 -2.4564555556,51.6342583333,182.88 -2.4611111111,51.6395611111,182.88 -2.4666166667,51.6397694444,182.88 -2.4776472222,51.6386305556,182.88 + + + + + + EGRU162 HMP ERLESTOKE + <table border="1" cellpadding="1" cellspacing="0" row_id="14071" txt_name="HMP ERLESTOKE"><tr><td>511726N 0020243W -<br/>511728N 0020206W -<br/>511703N 0020205W -<br/>511643N 0020217W -<br/>511650N 0020308W -<br/>511712N 0020324W -<br/>511726N 0020243W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 360 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0452722222,51.2906527778,243.84 -2.0567666667,51.2865527778,243.84 -2.0523444444,51.2805277778,243.84 -2.0381527778,51.2786583333,243.84 -2.0346833333,51.2842861111,243.84 -2.0350694444,51.2912138889,243.84 -2.0452722222,51.2906527778,243.84 + + + + + + EGRU163 HMP FELTHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="14072" txt_name="HMP FELTHAM"><tr><td>512644N 0002615W -<br/>512640N 0002532W -<br/>512559N 0002547W -<br/>512607N 0002647W -<br/>512639N 0002641W -<br/>512644N 0002615W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.<br/>NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 62 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4374555556,51.4456916667,152.4 -0.4445888889,51.4440722222,152.4 -0.4464194444,51.4351611111,152.4 -0.4298361111,51.4329861111,152.4 -0.4255777778,51.4443638889,152.4 -0.4374555556,51.4456916667,152.4 + + + + + + EGRU164 HMP GRENDON + <table border="1" cellpadding="1" cellspacing="0" row_id="14061" txt_name="HMP GRENDON"><tr><td>515354N 0010045W -<br/>515352N 0010002W -<br/>515339N 0005949W -<br/>515321N 0005949W -<br/>515310N 0010013W -<br/>515317N 0010046W -<br/>515332N 0010050W -<br/>515354N 0010045W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 296 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0123694444,51.8984361111,213.36 -1.01375,51.8922777778,213.36 -1.0127555556,51.8879388889,213.36 -1.0036888889,51.8861833333,213.36 -0.9968944444,51.8892388889,213.36 -0.9969638889,51.8942055556,213.36 -1.0004833333,51.8977416667,213.36 -1.0123694444,51.8984361111,213.36 + + + + + + EGRU165 HMP HUNTERCOMBE + <table border="1" cellpadding="1" cellspacing="0" row_id="14066" txt_name="HMP HUNTERCOMBE"><tr><td>513536N 0010124W -<br/>513528N 0010033W -<br/>513455N 0010046W -<br/>513504N 0010142W -<br/>513536N 0010124W <br/>Upper limit: 1100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 691 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0232222222,51.5932361111,335.28000000000003 -1.0283555556,51.5845388889,335.28000000000003 -1.0128361111,51.5818694444,335.28000000000003 -1.0091694444,51.5910694444,335.28000000000003 -1.0232222222,51.5932361111,335.28000000000003 + + + + + + EGRU166 HMP MAIDSTONE + <table border="1" cellpadding="1" cellspacing="0" row_id="14063" txt_name="HMP MAIDSTONE"><tr><td>511709N 0003128E -<br/>511642N 0003202E -<br/>511622N 0003124E -<br/>511648N 0003046E -<br/>511709N 0003128E <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 123 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5243527778,51.2857555556,182.88 0.5127555556,51.2800194444,182.88 0.5232944444,51.2726805556,182.88 0.5339416667,51.2783527778,182.88 0.5243527778,51.2857555556,182.88 + + + + + + EGRU167 HMP PARC + <table border="1" cellpadding="1" cellspacing="0" row_id="14146" txt_name="HMP PARC"><tr><td>513207N 0033404W -<br/>513211N 0033313W -<br/>513138N 0033308W -<br/>513133N 0033411W -<br/>513158N 0033416W -<br/>513207N 0033404W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 343 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.5678111111,51.5352527778,243.84 -3.5710222222,51.5326472222,243.84 -3.5698055556,51.5257222222,243.84 -3.5522638889,51.5271083333,243.84 -3.5535388889,51.5363333333,243.84 -3.5678111111,51.5352527778,243.84 + + + + + + EGRU168 HMP PENTONVILLE + <table border="1" cellpadding="1" cellspacing="0" row_id="14118" txt_name="HMP PENTONVILLE"><tr><td>513256N 0000726W -<br/>513258N 0000659W -<br/>513257N 0000641W -<br/>513231N 0000624W -<br/>513222N 0000721W -<br/>513256N 0000726W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 141 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1238444444,51.5488361111,182.88 -0.1224222222,51.5393944444,182.88 -0.1066055556,51.54205,182.88 -0.1114833333,51.5491972222,182.88 -0.1164833333,51.5494138889,182.88 -0.1238444444,51.5488361111,182.88 + + + + + + EGRU169 HMP ROCHESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="14060" txt_name="HMP ROCHESTER"><tr><td>512226N 0002853E -<br/>512227N 0002947E -<br/>512201N 0003010E -<br/>512147N 0003000E -<br/>512136N 0002947E -<br/>512137N 0002930E -<br/>512226N 0002853E <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Rochester Tower (FRZ - EGRU139A) and HMPPS.<br/>Contact: Rochester Tower 01634-869969 (Option 3 (Air Traffic Control)) Tower@rochesterairport.co.uk<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 326 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4812666667,51.3738055556,243.84 0.4916833333,51.3603027778,243.84 0.4963916667,51.3601055556,243.84 0.5000972222,51.3629972222,243.84 0.5027888889,51.3670333333,243.84 0.4962694444,51.3742805556,243.84 0.4812666667,51.3738055556,243.84 + + + + + + EGRU170 HMP SEND + <table border="1" cellpadding="1" cellspacing="0" row_id="14136" txt_name="HMP SEND"><tr><td>511647N 0002943W -<br/>511649N 0002911W -<br/>511610N 0002857W -<br/>511605N 0002942W -<br/>511620N 0002953W -<br/>511634N 0002958W -<br/>511647N 0002943W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 182 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4953472222,51.2797444444,182.88 -0.4993222222,51.2761944444,182.88 -0.4980666667,51.2721388889,182.88 -0.4950305556,51.2680138889,182.88 -0.4824361111,51.2694277778,182.88 -0.4863444444,51.2802666667,182.88 -0.4953472222,51.2797444444,182.88 + + + + + + EGRU171 HMP SWALESIDE/ELMLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14132" txt_name="HMP SWALESIDE/ELMLEY"><tr><td>512358N 0005051E -<br/>512345N 0005148E -<br/>512306N 0005126E -<br/>512259N 0005101E -<br/>512309N 0005025E -<br/>512358N 0005051E <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 73 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.8475638889,51.3994277778,152.4 0.8404138889,51.3857027778,152.4 0.8501388889,51.3830972222,152.4 0.8572611111,51.3849972222,152.4 0.8634527778,51.3958083333,152.4 0.8475638889,51.3994277778,152.4 + + + + + + EGRU172 HMP SWANSEA + <table border="1" cellpadding="1" cellspacing="0" row_id="14139" txt_name="HMP SWANSEA"><tr><td>513706N 0035719W -<br/>513711N 0035655W -<br/>513707N 0035636W -<br/>513647N 0035625W -<br/>513637N 0035706W -<br/>513647N 0035724W -<br/>513706N 0035719W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 27 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9554083333,51.6182055556,152.4 -3.9566,51.61305,152.4 -3.9516,51.6103583333,152.4 -3.9402194444,51.6129305556,152.4 -3.9434361111,51.6185388889,152.4 -3.9486805556,51.6196555556,152.4 -3.9554083333,51.6182055556,152.4 + + + + + + EGRU173 HMP THE MOUNT + <table border="1" cellpadding="1" cellspacing="0" row_id="14082" txt_name="HMP THE MOUNT"><tr><td>514353N 0003231W -<br/>514355N 0003207W -<br/>514340N 0003138W -<br/>514313N 0003213W -<br/>514315N 0003255W -<br/>514332N 0003253W -<br/>514343N 0003245W -<br/>514353N 0003231W <br/>Upper limit: 1000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 539 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5418638889,51.7313888889,304.8 -0.5458194444,51.7286388889,304.8 -0.54795,51.7256777778,304.8 -0.5487111111,51.7209111111,304.8 -0.5369555556,51.7203027778,304.8 -0.5273166667,51.7278194444,304.8 -0.5353611111,51.7318416667,304.8 -0.5418638889,51.7313888889,304.8 + + + + + + EGRU174 HMP USK + <table border="1" cellpadding="1" cellspacing="0" row_id="14107" txt_name="HMP USK"><tr><td>514218N 0025347W -<br/>514153N 0025327W -<br/>514139N 0025411W -<br/>514205N 0025433W -<br/>514218N 0025347W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 61 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8964611111,51.7049333333,152.4 -2.909075,51.7013416667,152.4 -2.9031472222,51.6940388889,152.4 -2.8909361111,51.6980722222,152.4 -2.8964611111,51.7049333333,152.4 + + + + + + EGRU175 HMP WANDSWORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="14102" txt_name="HMP WANDSWORTH"><tr><td>512722N 0001030W -<br/>512653N 0001006W -<br/>512636N 0001042W -<br/>512659N 0001111W -<br/>512714N 0001056W -<br/>512722N 0001030W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.<br/>London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 112 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1751111111,51.4561361111,182.88 -0.1822138889,51.4539194444,182.88 -0.1864583333,51.4496,182.88 -0.1783527778,51.4432166667,182.88 -0.1683916667,51.4481388889,182.88 -0.1751111111,51.4561361111,182.88 + + + + + + EGRU176 HMP WINCHESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="14124" txt_name="HMP WINCHESTER"><tr><td>510400N 0012008W -<br/>510409N 0011927W -<br/>510355N 0011917W -<br/>510334N 0011913W -<br/>510330N 0012001W -<br/>510400N 0012008W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 333 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3355916667,51.0667638889,243.84 -1.3336277778,51.0584444444,243.84 -1.3203583333,51.0595305556,243.84 -1.3214416667,51.0652861111,243.84 -1.3242,51.0690611111,243.84 -1.3355916667,51.0667638889,243.84 + + + + + + EGRU177 HMP WORMWOOD SCRUBS + <table border="1" cellpadding="1" cellspacing="0" row_id="14155" txt_name="HMP WORMWOOD SCRUBS"><tr><td>513116N 0001456W -<br/>513119N 0001401W -<br/>513047N 0001352W -<br/>513044N 0001445W -<br/>513057N 0001454W -<br/>513116N 0001456W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 51 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2490222222,51.5210527778,152.4 -0.2482861111,51.5157277778,152.4 -0.245725,51.51225,152.4 -0.2311805556,51.513125,152.4 -0.2334805556,51.5218972222,152.4 -0.2490222222,51.5210527778,152.4 + + + + + + EGRU201A WEST WALES/ABERPORTH + <table border="1" cellpadding="1" cellspacing="0" row_id="7565" txt_name="WEST WALES/ABERPORTH"><tr><td>A circle, 2 NM radius, centred at 520653N 0043334W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5594166667,52.1480051098,609.6 -4.5649804396,52.1478285462,609.6 -4.5704851043,52.1473007313,609.6 -4.5758721847,52.1464272721,609.6 -4.5810844621,52.1452174474,609.6 -4.5860665862,52.1436841082,609.6 -4.5907656665,52.1418435403,609.6 -4.595131836,52.1397152906,609.6 -4.5991187822,52.1373219582,609.6 -4.6026842393,52.1346889531,609.6 -4.6057904364,52.1318442253,609.6 -4.6084044967,52.1288179668,609.6 -4.610498784,52.1256422898,609.6 -4.6120511927,52.1223508853,609.6 -4.6130453778,52.1189786645,609.6 -4.6134709236,52.1155613879,609.6 -4.613323449,52.1121352855,609.6 -4.6126046482,52.1087366727,609.6 -4.6113222675,52.1054015654,609.6 -4.6094900176,52.1021652986,609.6 -4.6071274234,52.0990621525,609.6 -4.6042596129,52.0961249906,609.6 -4.6009170469,52.0933849121,609.6 -4.5971351939,52.090870924,609.6 -4.5929541522,52.0886096354,609.6 -4.588418225,52.0866249767,609.6 -4.5835754511,52.084937948,609.6 -4.5784770974,52.083566398,609.6 -4.5731771188,52.0825248361,609.6 -4.5677315897,52.0818242799,609.6 -4.5621981139,52.0814721395,609.6 -4.5566352195,52.0814721395,609.6 -4.5511017437,52.0818242799,609.6 -4.5456562145,52.0825248361,609.6 -4.5403562359,52.083566398,609.6 -4.5352578823,52.084937948,609.6 -4.5304151083,52.0866249767,609.6 -4.5258791811,52.0886096354,609.6 -4.5216981395,52.090870924,609.6 -4.5179162864,52.0933849121,609.6 -4.5145737204,52.0961249906,609.6 -4.5117059099,52.0990621525,609.6 -4.5093433158,52.1021652986,609.6 -4.5075110659,52.1054015654,609.6 -4.5062286851,52.1087366727,609.6 -4.5055098843,52.1121352855,609.6 -4.5053624097,52.1155613879,609.6 -4.5057879555,52.1189786645,609.6 -4.5067821406,52.1223508853,609.6 -4.5083345493,52.1256422898,609.6 -4.5104288367,52.1288179668,609.6 -4.513042897,52.1318442253,609.6 -4.516149094,52.1346889531,609.6 -4.5197145511,52.1373219582,609.6 -4.5237014973,52.1397152906,609.6 -4.5280676668,52.1418435403,609.6 -4.5327667471,52.1436841082,609.6 -4.5377488713,52.1452174474,609.6 -4.5429611486,52.1464272721,609.6 -4.548348229,52.1473007313,609.6 -4.5538528938,52.1478285462,609.6 -4.5594166667,52.1480051098,609.6 + + + + + + EGRU201B WEST WALES/ABERPORTH RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7699" txt_name="WEST WALES/ABERPORTH RWY 07"><tr><td>520543N 0043806W -<br/>520614N 0043822W -<br/>520633N 0043646W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to<br/>520602N 0043630W -<br/>520543N 0043806W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6350722222,52.0952472222,609.6 -4.6082841389,52.1004781111,609.6 -4.6101710488,52.1032481534,609.6 -4.6116450046,52.1061116413,609.6 -4.6126939167,52.1090452778,609.6 -4.6394694444,52.1038166667,609.6 -4.6350722222,52.0952472222,609.6 + + + + + + EGRU201C WEST WALES/ABERPORTH RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7799" txt_name="WEST WALES/ABERPORTH RWY 25"><tr><td>520803N 0042902W -<br/>520732N 0042846W -<br/>520713N 0043022W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to<br/>520744N 0043038W -<br/>520803N 0042902W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4837666667,52.1341194444,609.6 -4.5105152222,52.1289312222,609.6 -4.5086338997,52.1261593432,609.6 -4.5071664244,52.12329435,609.6 -4.5061246944,52.1203595833,609.6 -4.4793638889,52.12555,609.6 -4.4837666667,52.1341194444,609.6 + + + + + + EGRU202A WELSHPOOL + <table border="1" cellpadding="1" cellspacing="0" row_id="8116" txt_name="WELSHPOOL"><tr><td>A circle, 2 NM radius, centred at 523743N 0030912W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1532972222,52.6619383097,609.6 -3.1589260268,52.6617617591,609.6 -3.1644950299,52.661233983,609.6 -3.1699450695,52.6603605885,609.6 -3.1752182559,52.6591508538,609.6 -3.1802585903,52.6576176296,609.6 -3.1850125627,52.6557772011,609.6 -3.1894297226,52.6536491143,609.6 -3.1934632159,52.6512559674,609.6 -3.1970702834,52.6486231691,609.6 -3.2002127138,52.645778668,609.6 -3.2028572478,52.6427526543,609.6 -3.2049759285,52.6395772385,609.6 -3.2065463945,52.6362861091,609.6 -3.2075521128,52.6329141749,609.6 -3.2079825492,52.6294971935,609.6 -3.2078332746,52.6260713921,609.6 -3.2071060066,52.6226730826,609.6 -3.2058085849,52.6193382778,609.6 -3.2039548833,52.6161023088,609.6 -3.2015646572,52.6129994526,609.6 -3.1986633301,52.6100625687,609.6 -3.1952817199,52.6073227528,609.6 -3.19145571,52.6048090084,609.6 -3.1872258673,52.6025479412,609.6 -3.1826370117,52.6005634786,609.6 -3.1777377416,52.5988766179,609.6 -3.1725799209,52.5975052054,609.6 -3.167218132,52.5964637484,609.6 -3.1617091013,52.595763263,609.6 -3.156111102,52.5954111583,609.6 -3.1504833424,52.5954111583,609.6 -3.1448853432,52.595763263,609.6 -3.1393763124,52.5964637484,609.6 -3.1340145236,52.5975052054,609.6 -3.1288567029,52.5988766179,609.6 -3.1239574328,52.6005634786,609.6 -3.1193685771,52.6025479412,609.6 -3.1151387345,52.6048090084,609.6 -3.1113127246,52.6073227528,609.6 -3.1079311144,52.6100625687,609.6 -3.1050297872,52.6129994526,609.6 -3.1026395612,52.6161023088,609.6 -3.1007858596,52.6193382778,609.6 -3.0994884379,52.6226730826,609.6 -3.0987611698,52.6260713921,609.6 -3.0986118953,52.6294971935,609.6 -3.0990423317,52.6329141749,609.6 -3.1000480499,52.6362861091,609.6 -3.1016185159,52.6395772385,609.6 -3.1037371966,52.6427526543,609.6 -3.1063817306,52.645778668,609.6 -3.109524161,52.6486231691,609.6 -3.1131312286,52.6512559674,609.6 -3.1171647219,52.6536491143,609.6 -3.1215818817,52.6557772011,609.6 -3.1263358541,52.6576176296,609.6 -3.1313761886,52.6591508538,609.6 -3.136649375,52.6603605885,609.6 -3.1420994145,52.661233983,609.6 -3.1476684176,52.6617617591,609.6 -3.1532972222,52.6619383097,609.6 + + + + + + EGRU202B WELSHPOOL RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7949" txt_name="WELSHPOOL RWY 04"><tr><td>523510N 0031134W -<br/>523529N 0031218W -<br/>523615N 0031125W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to<br/>523556N 0031041W -<br/>523510N 0031134W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1928166667,52.5861333333,609.6 -3.1781366111,52.5989991389,609.6 -3.1824262144,52.6004823189,609.6 -3.186479086,52.6021947615,609.6 -3.19026225,52.6041225556,609.6 -3.2049305556,52.5912638889,609.6 -3.1928166667,52.5861333333,609.6 + + + + + + EGRU202C WELSHPOOL RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7596" txt_name="WELSHPOOL RWY 22"><tr><td>524016N 0030650W -<br/>523957N 0030606W -<br/>523911N 0030658W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to<br/>523930N 0030742W -<br/>524016N 0030650W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1138,52.671,609.6 -3.1283630833,52.6582820278,609.6 -3.1240726758,52.6567936288,609.6 -3.1200207057,52.6550759558,609.6 -3.1162401944,52.6531430278,609.6 -3.1016638889,52.6658694444,609.6 -3.1138,52.671,609.6 + + + + + + EGRU203A SHOBDON + <table border="1" cellpadding="1" cellspacing="0" row_id="7828" txt_name="SHOBDON"><tr><td>A circle, 2 NM radius, centred at 521430N 0025252W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8811111111,52.2749543894,609.6 -2.8866907656,52.274777829,609.6 -2.8922111426,52.2742500237,609.6 -2.8976135985,52.2733765806,609.6 -2.9028407506,52.2721667782,609.6 -2.9078370904,52.2706334675,609.6 -2.9125495762,52.2687929342,609.6 -2.9169281982,52.2666647249,609.6 -2.9209265119,52.2642714384,609.6 -2.9245021309,52.2616384845,609.6 -2.9276171767,52.2587938129,609.6 -2.9302386792,52.255767615,609.6 -2.9323389239,52.2525920027,609.6 -2.9338957425,52.2493006663,609.6 -2.9348927443,52.2459285165,609.6 -2.9353194846,52.2425113129,609.6 -2.9351715705,52.2390852849,609.6 -2.934450702,52.2356867472,609.6 -2.9331646481,52.2323517147,609.6 -2.9313271595,52.2291155216,609.6 -2.9289578173,52.2260124472,609.6 -2.9260818216,52.223075354,609.6 -2.9227297205,52.2203353404,609.6 -2.9189370837,52.2178214126,609.6 -2.9147441241,52.2155601787,609.6 -2.910195271,52.2135755685,609.6 -2.9053386998,52.2118885813,609.6 -2.9002258233,52.2105170653,609.6 -2.8949107497,52.2094755293,609.6 -2.8894497124,52.2087749906,609.6 -2.8839004789,52.208422859,609.6 -2.8783217433,52.208422859,609.6 -2.8727725099,52.2087749906,609.6 -2.8673114726,52.2094755293,609.6 -2.8619963989,52.2105170653,609.6 -2.8568835225,52.2118885813,609.6 -2.8520269513,52.2135755685,609.6 -2.8474780981,52.2155601787,609.6 -2.8432851385,52.2178214126,609.6 -2.8394925017,52.2203353404,609.6 -2.8361404006,52.223075354,609.6 -2.8332644049,52.2260124472,609.6 -2.8308950627,52.2291155216,609.6 -2.8290575741,52.2323517147,609.6 -2.8277715202,52.2356867472,609.6 -2.8270506517,52.2390852849,609.6 -2.8269027376,52.2425113129,609.6 -2.8273294779,52.2459285165,609.6 -2.8283264797,52.2493006663,609.6 -2.8298832984,52.2525920027,609.6 -2.831983543,52.255767615,609.6 -2.8346050455,52.2587938129,609.6 -2.8377200913,52.2616384845,609.6 -2.8412957103,52.2642714384,609.6 -2.845294024,52.2666647249,609.6 -2.8496726461,52.2687929342,609.6 -2.8543851318,52.2706334675,609.6 -2.8593814716,52.2721667782,609.6 -2.8646086238,52.2733765806,609.6 -2.8700110796,52.2742500237,609.6 -2.8755314566,52.274777829,609.6 -2.8811111111,52.2749543894,609.6 + + + + + + EGRU203B SHOBDON RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7905" txt_name="SHOBDON RWY 08"><tr><td>521352N 0025732W -<br/>521424N 0025739W -<br/>521431N 0025607W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to<br/>521359N 0025600W -<br/>521352N 0025732W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9589777778,52.2310055556,609.6 -2.9334707778,52.2330216667,609.6 -2.9345288123,52.2359549995,609.6 -2.9351518764,52.2389349498,609.6 -2.9353348056,52.24193725,609.6 -2.9608333333,52.2399222222,609.6 -2.9589777778,52.2310055556,609.6 + + + + + + EGRU203C SHOBDON RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7778" txt_name="SHOBDON RWY 26"><tr><td>521508N 0024813W -<br/>521436N 0024806W -<br/>521429N 0024937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to<br/>521501N 0024943W -<br/>521508N 0024813W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.803475,52.2522666667,609.6 -2.828736,52.2502995833,609.6 -2.8276831046,52.2473661174,609.6 -2.8270654286,52.2443863328,609.6 -2.8268879167,52.2413845,609.6 -2.8016166667,52.2433527778,609.6 -2.803475,52.2522666667,609.6 + + + + + + EGRU204A SLEAP + <table border="1" cellpadding="1" cellspacing="0" row_id="7973" txt_name="SLEAP"><tr><td>A circle, 2 NM radius, centred at 525002N 0024618W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7716666667,52.8671732622,609.6 -2.7773219972,52.8669967167,609.6 -2.7829172434,52.8664689561,609.6 -2.7883929636,52.8655955872,609.6 -2.7936909943,52.8643858882,609.6 -2.7987550722,52.8628527096,609.6 -2.8035314345,52.8610123364,609.6 -2.8079693927,52.8588843143,609.6 -2.8120218721,52.8564912409,609.6 -2.8156459119,52.8538585248,609.6 -2.8188031213,52.8510141137,609.6 -2.8214600849,52.8479881974,609.6 -2.8235887151,52.8448128853,609.6 -2.8251665461,52.8415218654,609.6 -2.8261769682,52.8381500451,609.6 -2.8266093991,52.8347331812,609.6 -2.82645939,52.8313074995,609.6 -2.8257286679,52.8279093109,609.6 -2.8244251109,52.8245746265,609.6 -2.8225626591,52.8213387762,609.6 -2.8201611621,52.8182360355,609.6 -2.8172461638,52.8152992624,609.6 -2.8138486278,52.8125595511,609.6 -2.8100046069,52.8100459039,609.6 -2.805754859,52.807784925,609.6 -2.8011444147,52.8058005407,609.6 -2.7962221007,52.8041137471,609.6 -2.7910400244,52.8027423894,609.6 -2.7856530242,52.8017009742,609.6 -2.7801180923,52.8010005171,609.6 -2.7744937751,52.8006484267,609.6 -2.7688395582,52.8006484267,609.6 -2.763215241,52.8010005171,609.6 -2.7576803091,52.8017009742,609.6 -2.7522933089,52.8027423894,609.6 -2.7471112326,52.8041137471,609.6 -2.7421889187,52.8058005407,609.6 -2.7375784743,52.807784925,609.6 -2.7333287264,52.8100459039,609.6 -2.7294847055,52.8125595511,609.6 -2.7260871695,52.8152992624,609.6 -2.7231721712,52.8182360355,609.6 -2.7207706742,52.8213387762,609.6 -2.7189082225,52.8245746265,609.6 -2.7176046654,52.8279093109,609.6 -2.7168739433,52.8313074995,609.6 -2.7167239343,52.8347331812,609.6 -2.7171563651,52.8381500451,609.6 -2.7181667872,52.8415218654,609.6 -2.7197446182,52.8448128853,609.6 -2.7218732484,52.8479881974,609.6 -2.7245302121,52.8510141137,609.6 -2.7276874215,52.8538585248,609.6 -2.7313114613,52.8564912409,609.6 -2.7353639406,52.8588843143,609.6 -2.7398018988,52.8610123364,609.6 -2.7445782612,52.8628527096,609.6 -2.7496423391,52.8643858882,609.6 -2.7549403698,52.8655955872,609.6 -2.7604160899,52.8664689561,609.6 -2.7660113361,52.8669967167,609.6 -2.7716666667,52.8671732622,609.6 + + + + + + EGRU204B SLEAP RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8022" txt_name="SLEAP RWY 05"><tr><td>524748N 0024923W -<br/>524811N 0025001W -<br/>524850N 0024856W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to<br/>524827N 0024818W -<br/>524748N 0024923W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8230305556,52.796675,609.6 -2.8051105556,52.8074808889,609.6 -2.8089038559,52.8094142415,609.6 -2.8123944447,52.8115468244,609.6 -2.8155538889,52.8138613056,609.6 -2.8334805556,52.80305,609.6 -2.8230305556,52.796675,609.6 + + + + + + EGRU204C SLEAP RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7822" txt_name="SLEAP RWY 23"><tr><td>525217N 0024311W -<br/>525154N 0024234W -<br/>525114N 0024340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to<br/>525137N 0024418W -<br/>525217N 0024311W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7198416667,52.8714472222,609.6 -2.7383165278,52.8603496111,609.6 -2.7345122636,52.8584212007,609.6 -2.7310110402,52.8562929696,609.6 -2.7278413611,52.8539822778,609.6 -2.7093722222,52.865075,609.6 -2.7198416667,52.8714472222,609.6 + + + + + + EGRU204D SLEAP RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7739" txt_name="SLEAP RWY 18"><tr><td>525253N 0024646W -<br/>525253N 0024553W -<br/>525201N 0024551W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to<br/>525201N 0024644W -<br/>525253N 0024646W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7795583333,52.8812833333,609.6 -2.7789823611,52.8668773056,609.6 -2.7740367547,52.8671423114,609.6 -2.7690717949,52.8671361609,609.6 -2.7641280278,52.8668588889,609.6 -2.7647083333,52.8815,609.6 -2.7795583333,52.8812833333,609.6 + + + + + + EGRU204E SLEAP RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7765" txt_name="SLEAP RWY 36"><tr><td>524705N 0024539W -<br/>524704N 0024633W -<br/>524803N 0024635W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to<br/>524804N 0024542W -<br/>524705N 0024539W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7608805556,52.7847416667,609.6 -2.7615295,52.8011758333,609.6 -2.7664380394,52.8007554016,609.6 -2.7713890858,52.8006047438,609.6 -2.7763423889,52.8007250833,609.6 -2.7756972222,52.7845277778,609.6 -2.7608805556,52.7847416667,609.6 + + + + + + EGRU205A SHAWBURY + <table border="1" cellpadding="1" cellspacing="0" row_id="8154" txt_name="SHAWBURY"><tr><td>A circle, 2 NM radius, centred at 524737N 0024005W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6679388889,52.8269096004,609.6 -2.67358899,52.8267330539,609.6 -2.6791790626,52.8262052903,609.6 -2.6846497199,52.8253319163,609.6 -2.6899428528,52.8241222104,609.6 -2.6950022498,52.8225890229,609.6 -2.6997741981,52.8207486388,609.6 -2.7042080561,52.818620604,609.6 -2.7082567924,52.8162275163,609.6 -2.7118774863,52.813594784,609.6 -2.7150317821,52.8107503553,609.6 -2.7176862954,52.8077244199,609.6 -2.7198129641,52.8045490875,609.6 -2.7213893431,52.8012580461,609.6 -2.7223988379,52.7978862036,609.6 -2.7228308756,52.7944693166,609.6 -2.7226810114,52.7910436115,609.6 -2.7219509703,52.7876453991,609.6 -2.7206486227,52.7843106911,609.6 -2.718787896,52.7810748176,609.6 -2.716388621,52.7779720542,609.6 -2.7134763179,52.7750352593,609.6 -2.7100819216,52.7722955276,609.6 -2.7062414514,52.7697818613,609.6 -2.7019956277,52.7675208651,609.6 -2.6973894394,52.7655364654,609.6 -2.6924716684,52.7638496586,609.6 -2.6872943739,52.7624782902,609.6 -2.6819123439,52.7614368668,609.6 -2.6763825182,52.7607364042,609.6 -2.6707633894,52.7603843109,609.6 -2.6651143884,52.7603843109,609.6 -2.6594952596,52.7607364042,609.6 -2.6539654339,52.7614368668,609.6 -2.6485834039,52.7624782902,609.6 -2.6434061094,52.7638496586,609.6 -2.6384883384,52.7655364654,609.6 -2.6338821501,52.7675208651,609.6 -2.6296363263,52.7697818613,609.6 -2.6257958562,52.7722955276,609.6 -2.6224014599,52.7750352593,609.6 -2.6194891568,52.7779720542,609.6 -2.6170898818,52.7810748176,609.6 -2.615229155,52.7843106911,609.6 -2.6139268075,52.7876453991,609.6 -2.6131967664,52.7910436115,609.6 -2.6130469022,52.7944693166,609.6 -2.6134789398,52.7978862036,609.6 -2.6144884347,52.8012580461,609.6 -2.6160648137,52.8045490875,609.6 -2.6181914824,52.8077244199,609.6 -2.6208459957,52.8107503553,609.6 -2.6240002915,52.813594784,609.6 -2.6276209853,52.8162275163,609.6 -2.6316697217,52.818620604,609.6 -2.6361035797,52.8207486388,609.6 -2.640875528,52.8225890229,609.6 -2.645934925,52.8241222104,609.6 -2.6512280578,52.8253319163,609.6 -2.6566987152,52.8262052903,609.6 -2.6622887877,52.8267330539,609.6 -2.6679388889,52.8269096004,609.6 + + + + + + EGRU205B SHAWBURY RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7548" txt_name="SHAWBURY RWY 05"><tr><td>524527N 0024325W -<br/>524550N 0024403W -<br/>524633N 0024252W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to<br/>524609N 0024218W -<br/>524527N 0024325W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7235820278,52.7576245833,609.6 -2.7049352778,52.7690354444,609.6 -2.7084554449,52.7711671052,609.6 -2.7116432321,52.7734832474,609.6 -2.7144724444,52.7759648611,609.6 -2.7340958611,52.7639548056,609.6 -2.7235820278,52.7576245833,609.6 + + + + + + EGRU205C SHAWBURY RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="8020" txt_name="SHAWBURY RWY 23"><tr><td>525011N 0023655W -<br/>524949N 0023617W -<br/>524858N 0023740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to<br/>524919N 0023821W -<br/>525011N 0023655W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6153044722,52.8365074722,609.6 -2.6391511389,52.8219718889,609.6 -2.6350330637,52.8202752714,609.6 -2.631185824,52.8183596115,609.6 -2.6276410556,52.8162406667,609.6 -2.6047731389,52.8301773333,609.6 -2.6153044722,52.8365074722,609.6 + + + + + + EGRU205D SHAWBURY RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7951" txt_name="SHAWBURY RWY 18"><tr><td>525048N 0024032W -<br/>525048N 0023939W -<br/>524936N 0023938W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to<br/>524936N 0024032W -<br/>525048N 0024032W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6755396111,52.84677375,609.6 -2.6754679167,52.8265954444,609.6 -2.6705304301,52.826872528,609.6 -2.6655717917,52.8268786728,609.6 -2.6606324722,52.8266138333,609.6 -2.6606972778,52.8467921389,609.6 -2.6755396111,52.84677375,609.6 + + + + + + EGRU205E SHAWBURY RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7630" txt_name="SHAWBURY RWY 36"><tr><td>524426N 0023937W -<br/>524426N 0024031W -<br/>524538N 0024031W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to<br/>524538N 0023938W -<br/>524426N 0023937W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6603565556,52.7404752778,609.6 -2.6604210833,52.7606538889,609.6 -2.6653511557,52.7603772366,609.6 -2.6703022476,52.7603710937,609.6 -2.6752341389,52.7606355278,609.6 -2.6751627778,52.7404568889,609.6 -2.6603565556,52.7404752778,609.6 + + + + + + EGRU206A TERNHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="7594" txt_name="TERNHILL"><tr><td>A circle, 2 NM radius, centred at 525223N 0023156W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5321916667,52.9064452629,609.6 -2.5378521099,52.9062687185,609.6 -2.5434524143,52.9057409608,609.6 -2.5489330842,52.9048675968,609.6 -2.5542359034,52.9036579047,609.6 -2.5593045577,52.9021247347,609.6 -2.5640852355,52.9002843721,609.6 -2.5685272025,52.8981563623,609.6 -2.5725833412,52.895763303,609.6 -2.5762106523,52.8931306025,609.6 -2.5793707102,52.8902862087,609.6 -2.5820300695,52.8872603109,609.6 -2.5841606174,52.8840850187,609.6 -2.5857398679,52.8807940196,609.6 -2.5867511966,52.8774222212,609.6 -2.5871840119,52.8740053798,609.6 -2.5870338612,52.870579721,609.6 -2.5863024734,52.8671815554,609.6 -2.5849977337,52.863846894,609.6 -2.5831335954,52.8606110665,609.6 -2.5807299261,52.8575083478,609.6 -2.5778122927,52.8545715958,609.6 -2.5744116872,52.8518319046,609.6 -2.5705641948,52.849318276,609.6 -2.5663106103,52.847057314,609.6 -2.5616960049,52.8450729446,609.6 -2.5567692495,52.8433861638,609.6 -2.5515824981,52.8420148166,609.6 -2.5461906387,52.8409734095,609.6 -2.5406507145,52.8402729578,609.6 -2.5350213248,52.8399208701,609.6 -2.5293620085,52.8399208701,609.6 -2.5237326188,52.8402729578,609.6 -2.5181926947,52.8409734095,609.6 -2.5128008352,52.8420148166,609.6 -2.5076140839,52.8433861638,609.6 -2.5026873284,52.8450729446,609.6 -2.498072723,52.847057314,609.6 -2.4938191385,52.849318276,609.6 -2.4899716461,52.8518319046,609.6 -2.4865710406,52.8545715958,609.6 -2.4836534073,52.8575083478,609.6 -2.4812497379,52.8606110665,609.6 -2.4793855996,52.863846894,609.6 -2.47808086,52.8671815554,609.6 -2.4773494721,52.870579721,609.6 -2.4771993215,52.8740053798,609.6 -2.4776321367,52.8774222212,609.6 -2.4786434655,52.8807940196,609.6 -2.480222716,52.8840850187,609.6 -2.4823532638,52.8872603109,609.6 -2.4850126232,52.8902862087,609.6 -2.4881726811,52.8931306025,609.6 -2.4917999922,52.895763303,609.6 -2.4958561309,52.8981563623,609.6 -2.5002980978,52.9002843721,609.6 -2.5050787756,52.9021247347,609.6 -2.5101474299,52.9036579047,609.6 -2.5154502492,52.9048675968,609.6 -2.520930919,52.9057409608,609.6 -2.5265312234,52.9062687185,609.6 -2.5321916667,52.9064452629,609.6 + + + + + + EGRU206B TERNHILL RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="8100" txt_name="TERNHILL RWY 04"><tr><td>525004N 0023450W -<br/>525026N 0023529W -<br/>525107N 0023428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525045N 0023348W -<br/>525004N 0023450W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5805501389,52.8343893333,609.6 -2.5634260556,52.8457666667,609.6 -2.5673785486,52.847581813,609.6 -2.5710450266,52.8496051651,609.6 -2.5743956389,52.8518202778,609.6 -2.5915122222,52.8404460278,609.6 -2.5805501389,52.8343893333,609.6 + + + + + + EGRU206C TERNHILL RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7619" txt_name="TERNHILL RWY 22"><tr><td>525443N 0022902W -<br/>525421N 0022822W -<br/>525340N 0022924W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525402N 0023003W -<br/>525443N 0022902W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4837607222,52.9119084722,609.6 -2.5009221944,52.900549,609.6 -2.4969673837,52.8987318797,609.6 -2.4932998953,52.8967064683,609.6 -2.4899496111,52.8944892778,609.6 -2.4727806111,52.9058518611,609.6 -2.4837607222,52.9119084722,609.6 + + + + + + EGRU206D TERNHILL RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="8017" txt_name="TERNHILL RWY 10"><tr><td>525233N 0023651W -<br/>525305N 0023643W -<br/>525256N 0023506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525224N 0023514W -<br/>525233N 0023651W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6141188611,52.8759196389,609.6 -2.5872000556,52.8733867778,609.6 -2.5869443115,52.876386522,609.6 -2.5862425569,52.879360097,609.6 -2.5851004167,52.8822832778,609.6 -2.6118228056,52.8847976389,609.6 -2.6141188611,52.8759196389,609.6 + + + + + + EGRU206E TERNHILL RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7878" txt_name="TERNHILL RWY 28"><tr><td>525212N 0022717W -<br/>525140N 0022725W -<br/>525148N 0022847W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525219N 0022838W -<br/>525212N 0022717W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4546785556,52.8699211389,609.6 -2.4772125278,52.8720677778,609.6 -2.4776011819,52.8690732605,609.6 -2.4784342929,52.8661121323,609.6 -2.479705,52.8632085,609.6 -2.4569738333,52.8610431111,609.6 -2.4546785556,52.8699211389,609.6 + + + + + + EGRU206F TERNHILL RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7918" txt_name="TERNHILL RWY 17"><tr><td>525513N 0023310W -<br/>525520N 0023217W -<br/>525423N 0023159W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525418N 0023252W -<br/>525513N 0023310W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5527453056,52.9203575,609.6 -2.547651,52.9051048889,609.6 -2.5428192861,52.9058186705,609.6 -2.5379006231,52.906265669,609.6 -2.53293525,52.9064422222,609.6 -2.5381707222,52.9221333889,609.6 -2.5527453056,52.9203575,609.6 + + + + + + EGRU206G TERNHILL RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7844" txt_name="TERNHILL RWY 35"><tr><td>524937N 0023023W -<br/>524931N 0023116W -<br/>525024N 0023134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to<br/>525032N 0023042W -<br/>524937N 0023023W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.50649125,52.8270092778,609.6 -2.5115754722,52.8423044722,609.6 -2.5162593978,52.84130443,609.6 -2.5210730991,52.8405642633,609.6 -2.5259773611,52.84009,609.6 -2.521034,52.8252333889,609.6 -2.50649125,52.8270092778,609.6 + + + + + + EGRU207A COSFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="8085" txt_name="COSFORD"><tr><td>A circle, 2 NM radius, centred at 523826N 0021819W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3052,52.6737854649,609.6 -2.3108303271,52.6736089147,609.6 -2.3164008364,52.6730811395,609.6 -2.3218523499,52.6722077464,609.6 -2.3271269622,52.6709980139,609.6 -2.3321686594,52.6694647923,609.6 -2.3369239169,52.6676243669,609.6 -2.3413422704,52.6654962839,609.6 -2.3453768535,52.6631031412,609.6 -2.3489848951,52.6604703477,609.6 -2.3521281738,52.6576258518,609.6 -2.3547734212,52.6545998437,609.6 -2.356892673,52.6514244339,609.6 -2.3584635616,52.6481333109,609.6 -2.3594695499,52.6447613832,609.6 -2.3599001008,52.6413444087,609.6 -2.3597507841,52.6379186141,609.6 -2.3590233178,52.6345203117,609.6 -2.3577255439,52.6311855137,609.6 -2.3558713401,52.6279495517,609.6 -2.3534804672,52.6248467021,609.6 -2.3505783554,52.6219098246,609.6 -2.3471958311,52.6191700147,609.6 -2.3433687875,52.6166562759,609.6 -2.3391378023,52.6143952138,609.6 -2.3345477076,52.6124107558,609.6 -2.3296471149,52.610723899,609.6 -2.3244879021,52.6093524896,609.6 -2.3191246662,52.608311035,609.6 -2.3136141488,52.6076105513,609.6 -2.3080146391,52.6072584474,609.6 -2.3023853609,52.6072584474,609.6 -2.2967858512,52.6076105513,609.6 -2.2912753338,52.608311035,609.6 -2.2859120979,52.6093524896,609.6 -2.2807528851,52.610723899,609.6 -2.2758522924,52.6124107558,609.6 -2.2712621977,52.6143952138,609.6 -2.2670312125,52.6166562759,609.6 -2.2632041689,52.6191700147,609.6 -2.2598216446,52.6219098246,609.6 -2.2569195328,52.6248467021,609.6 -2.2545286599,52.6279495517,609.6 -2.2526744561,52.6311855137,609.6 -2.2513766822,52.6345203117,609.6 -2.2506492159,52.6379186141,609.6 -2.2504998992,52.6413444087,609.6 -2.2509304501,52.6447613832,609.6 -2.2519364384,52.6481333109,609.6 -2.253507327,52.6514244339,609.6 -2.2556265788,52.6545998437,609.6 -2.2582718262,52.6576258518,609.6 -2.2614151049,52.6604703477,609.6 -2.2650231465,52.6631031412,609.6 -2.2690577296,52.6654962839,609.6 -2.2734760831,52.6676243669,609.6 -2.2782313406,52.6694647923,609.6 -2.2832730378,52.6709980139,609.6 -2.2885476501,52.6722077464,609.6 -2.2939991636,52.6730811395,609.6 -2.2995696729,52.6736089147,609.6 -2.3052,52.6737854649,609.6 + + + + + + EGRU207B COSFORD RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8004" txt_name="COSFORD RWY 06"><tr><td>523637N 0022215W -<br/>523704N 0022243W -<br/>523737N 0022118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to<br/>523709N 0022050W -<br/>523637N 0022215W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3708121389,52.6102927222,609.6 -2.3473025278,52.619248,609.6 -2.3502802235,52.6216433353,609.6 -2.3528913183,52.624192216,609.6 -2.3551145,52.6268739167,609.6 -2.3786348056,52.6179139722,609.6 -2.3708121389,52.6102927222,609.6 + + + + + + EGRU207C COSFORD RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="8185" txt_name="COSFORD RWY 24"><tr><td>524015N 0021423W -<br/>523947N 0021355W -<br/>523915N 0021519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to<br/>523943N 0021547W -<br/>524015N 0021423W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2396455556,52.6707405556,609.6 -2.26317,52.6618198889,609.6 -2.2601815668,52.6594282563,609.6 -2.2575601865,52.6568824958,609.6 -2.2553271667,52.6542033611,609.6 -2.2318134444,52.6631193889,609.6 -2.2396455556,52.6707405556,609.6 + + + + + + EGRU207D COSFORD RWY 06L + <table border="1" cellpadding="1" cellspacing="0" row_id="8027" txt_name="COSFORD RWY 06L"><tr><td>523639N 0022217W -<br/>523707N 0022245W -<br/>523739N 0022120W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to<br/>523711N 0022053W -<br/>523639N 0022217W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3714746389,52.6108995278,609.6 -2.3480534722,52.6198109722,609.6 -2.3509455268,52.6222458531,609.6 -2.3534653466,52.6248294636,609.6 -2.3555923611,52.6275407778,609.6 -2.3792911389,52.6185231667,609.6 -2.3714746389,52.6108995278,609.6 + + + + + + EGRU207E COSFORD RWY 24R + <table border="1" cellpadding="1" cellspacing="0" row_id="7538" txt_name="COSFORD RWY 24R"><tr><td>524016N 0021428W -<br/>523948N 0021359W -<br/>523917N 0021521W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to<br/>523944N 0021550W -<br/>524016N 0021428W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2410140556,52.6710197778,609.6 -2.2639089722,52.6623476389,609.6 -2.260838454,52.6599937279,609.6 -2.2581298286,52.6574809994,609.6 -2.2558051389,52.6548299444,609.6 -2.2331881944,52.6633962222,609.6 -2.2410140556,52.6710197778,609.6 + + + + + + EGRU208A WOLVERHAMPTON/HALFPENNY GREEN + <table border="1" cellpadding="1" cellspacing="0" row_id="7946" txt_name="WOLVERHAMPTON/HALFPENNY GREEN"><tr><td>A circle, 2 NM radius, centred at 523103N 0021534W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2595472222,52.5506694943,609.6 -2.2651617798,52.550492941,609.6 -2.2707166877,52.5499651565,609.6 -2.2761529343,52.549091748,609.6 -2.2814127768,52.547881994,609.6 -2.2864403587,52.5463487449,609.6 -2.2911823054,52.5445082863,609.6 -2.2955882944,52.5423801644,609.6 -2.2996115904,52.5399869775,609.6 -2.303209542,52.5373541345,609.6 -2.3063440346,52.5345095845,609.6 -2.3089818926,52.5314835179,609.6 -2.3110952293,52.5283080457,609.6 -2.3126617395,52.5250168569,609.6 -2.3136649312,52.5216448608,609.6 -2.3140942963,52.5182278157,609.6 -2.3139454162,52.5148019491,609.6 -2.3132200032,52.5114035741,609.6 -2.3119258767,52.5080687039,609.6 -2.3100768748,52.5048326706,609.6 -2.3076927023,52.5017297516,609.6 -2.3047987179,52.4987928076,609.6 -2.3014256614,52.4960529349,609.6 -2.2976093253,52.4935391378,609.6 -2.2933901738,52.4912780227,609.6 -2.2888129135,52.4892935177,609.6 -2.2839260204,52.4876066206,609.6 -2.2787812274,52.4862351784,609.6 -2.2734329797,52.4851936987,609.6 -2.2679378606,52.484493198,609.6 -2.2623539968,52.4841410855,609.6 -2.2567404476,52.4841410855,609.6 -2.2511565839,52.484493198,609.6 -2.2456614647,52.4851936987,609.6 -2.240313217,52.4862351784,609.6 -2.2351684241,52.4876066206,609.6 -2.2302815309,52.4892935177,609.6 -2.2257042707,52.4912780227,609.6 -2.2214851191,52.4935391378,609.6 -2.217668783,52.4960529349,609.6 -2.2142957265,52.4987928076,609.6 -2.2114017421,52.5017297516,609.6 -2.2090175697,52.5048326706,609.6 -2.2071685677,52.5080687039,609.6 -2.2058744412,52.5114035741,609.6 -2.2051490283,52.5148019491,609.6 -2.2050001482,52.5182278157,609.6 -2.2054295133,52.5216448608,609.6 -2.206432705,52.5250168569,609.6 -2.2079992151,52.5283080457,609.6 -2.2101125519,52.5314835179,609.6 -2.2127504099,52.5345095845,609.6 -2.2158849024,52.5373541345,609.6 -2.2194828541,52.5399869775,609.6 -2.22350615,52.5423801644,609.6 -2.227912139,52.5445082863,609.6 -2.2326540858,52.5463487449,609.6 -2.2376816676,52.547881994,609.6 -2.2429415102,52.549091748,609.6 -2.2483777568,52.5499651565,609.6 -2.2539326647,52.550492941,609.6 -2.2595472222,52.5506694943,609.6 + + + + + + EGRU208B WOLVERHAMPTON/HALFPENNY GREEN RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7965" txt_name="WOLVERHAMPTON/HALFPENNY GREEN RWY 04"><tr><td>522840N 0021816W -<br/>522859N 0021859W -<br/>522945N 0021803W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to<br/>522923N 0021724W -<br/>522840N 0021816W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3045555556,52.4777166667,609.6 -2.2899011667,52.4897268611,609.6 -2.2938762625,52.4915154092,609.6 -2.2975703338,52.4935160039,609.6 -2.3009530833,52.4957122778,609.6 -2.3163527778,52.4830888889,609.6 -2.3045555556,52.4777166667,609.6 + + + + + + EGRU208C WOLVERHAMPTON/HALFPENNY GREEN RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7663" txt_name="WOLVERHAMPTON/HALFPENNY GREEN RWY 22"><tr><td>523332N 0021326W -<br/>523313N 0021243W -<br/>523235N 0021329W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to<br/>523252N 0021414W -<br/>523332N 0021326W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2237694444,52.5588416667,609.6 -2.2373114444,52.5477822778,609.6 -2.2328922036,52.5464304954,609.6 -2.2286919692,52.54484039,609.6 -2.2247452222,52.5430250278,609.6 -2.21195,52.5534722222,609.6 -2.2237694444,52.5588416667,609.6 + + + + + + EGRU208D WOLVERHAMPTON/HALFPENNY GREEN RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="8016" txt_name="WOLVERHAMPTON/HALFPENNY GREEN RWY 16"><tr><td>523335N 0021755W -<br/>523348N 0021707W -<br/>523258N 0021630W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to<br/>523244N 0021718W -<br/>523335N 0021755W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2987055556,52.5595916667,609.6 -2.2884155278,52.54563275,609.6 -2.2841209325,52.5471052761,609.6 -2.2796258124,52.5483356141,609.6 -2.2749668333,52.5493137222,609.6 -2.28525,52.5632694444,609.6 -2.2987055556,52.5595916667,609.6 + + + + + + EGRU208E WOLVERHAMPTON/HALFPENNY GREEN RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="8186" txt_name="WOLVERHAMPTON/HALFPENNY GREEN RWY 34"><tr><td>522830N 0021313W -<br/>522816N 0021401W -<br/>522908N 0021439W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to<br/>522921N 0021351W -<br/>522830N 0021313W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2202611111,52.4749055556,609.6 -2.2307041944,52.4891311944,609.6 -2.2349940211,52.4876600186,609.6 -2.2394833707,52.4864307253,609.6 -2.24413575,52.4854533056,609.6 -2.2336861111,52.471225,609.6 -2.2202611111,52.4749055556,609.6 + + + + + + EGRU209A TATENHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="7910" txt_name="TATENHILL"><tr><td>A circle, 2 NM radius, centred at 524851N 0014553W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7647083333,52.8473539295,609.6 -1.7703610882,52.8471773836,609.6 -1.7759537862,52.8466496214,609.6 -1.7814270127,52.8457762501,609.6 -1.786722631,52.8445665477,609.6 -1.7917844034,52.8430333647,609.6 -1.7965585917,52.8411929861,609.6 -1.8009945304,52.8390649577,609.6 -1.8050451662,52.8366718773,609.6 -1.808667558,52.8340391532,609.6 -1.8118233323,52.8311947335,609.6 -1.8144790891,52.8281688078,609.6 -1.8166067531,52.8249934857,609.6 -1.818183869,52.8217024552,609.6 -1.8191938344,52.818330624,609.6 -1.8196260716,52.8149137488,609.6 -1.8194761339,52.8114880555,609.6 -1.8187457472,52.8080898552,609.6 -1.8174427859,52.8047551592,609.6 -1.8155811838,52.8015192975,609.6 -1.8131807812,52.7984165455,609.6 -1.8102671103,52.7954797617,609.6 -1.8068711208,52.7927400404,609.6 -1.8030288488,52.7902263838,609.6 -1.7987810336,52.7879653964,609.6 -1.7941726856,52.7859810045,609.6 -1.7892526091,52.7842942044,609.6 -1.7840728881,52.7829228414,609.6 -1.7786883359,52.7818814222,609.6 -1.773155919,52.7811809624,609.6 -1.7675341573,52.7808288706,609.6 -1.7618825094,52.7808288706,609.6 -1.7562607477,52.7811809624,609.6 -1.7507283308,52.7818814222,609.6 -1.7453437786,52.7829228414,609.6 -1.7401640575,52.7842942044,609.6 -1.7352439811,52.7859810045,609.6 -1.730635633,52.7879653964,609.6 -1.7263878179,52.7902263838,609.6 -1.7225455459,52.7927400404,609.6 -1.7191495563,52.7954797617,609.6 -1.7162358855,52.7984165455,609.6 -1.7138354829,52.8015192975,609.6 -1.7119738808,52.8047551592,609.6 -1.7106709195,52.8080898552,609.6 -1.7099405328,52.8114880555,609.6 -1.7097905951,52.8149137488,609.6 -1.7102228322,52.818330624,609.6 -1.7112327977,52.8217024552,609.6 -1.7128099135,52.8249934857,609.6 -1.7149375776,52.8281688078,609.6 -1.7175933343,52.8311947335,609.6 -1.7207491087,52.8340391532,609.6 -1.7243715005,52.8366718773,609.6 -1.7284221363,52.8390649577,609.6 -1.7328580749,52.8411929861,609.6 -1.7376322632,52.8430333647,609.6 -1.7426940356,52.8445665477,609.6 -1.7479896539,52.8457762501,609.6 -1.7534628805,52.8466496214,609.6 -1.7590555784,52.8471773836,609.6 -1.7647083333,52.8473539295,609.6 + + + + + + EGRU209B TATENHILL RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7622" txt_name="TATENHILL RWY 08"><tr><td>524744N 0015032W -<br/>524815N 0015047W -<br/>524833N 0014908W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to<br/>524802N 0014853W -<br/>524744N 0015032W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8422166667,52.7956138889,609.6 -1.8148514167,52.8004843611,609.6 -1.8166692181,52.8032777906,609.6 -1.8180644306,52.8061591203,609.6 -1.8190256111,52.8091049167,609.6 -1.8463805556,52.8042361111,609.6 -1.8422166667,52.7956138889,609.6 + + + + + + EGRU209C TATENHILL RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7643" txt_name="TATENHILL RWY 26"><tr><td>524957N 0014114W -<br/>524926N 0014059W -<br/>524908N 0014237W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to<br/>524939N 0014252W -<br/>524957N 0014114W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6871555556,52.8324722222,609.6 -1.7145350278,52.8276346944,609.6 -1.7127224882,52.8248396575,609.6 -1.7113333994,52.8219570266,609.6 -1.710379,52.8190102778,609.6 -1.6829861111,52.82385,609.6 -1.6871555556,52.8324722222,609.6 + + + + + + EGRU210A BIRMINGHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="8097" txt_name="BIRMINGHAM"><tr><td>A circle, 2.5 NM radius, centred at 522722N 0014502W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7505555556,52.4977192163,609.6 -1.7568458982,52.497541557,609.6 -1.763082423,52.4970100989,609.6 -1.7692117761,52.496129389,609.6 -1.7751815286,52.4949069615,609.6 -1.7809406276,52.4933532735,609.6 -1.7864398366,52.4914816145,609.6 -1.7916321586,52.4893079919,609.6 -1.7964732401,52.4868509931,609.6 -1.8009217512,52.4841316255,609.6 -1.8049397389,52.4811731357,609.6 -1.8084929515,52.4780008096,609.6 -1.8115511291,52.4746417551,609.6 -1.8140882605,52.4711246695,609.6 -1.8160828021,52.467479593,609.6 -1.8175178582,52.4637376518,609.6 -1.8183813209,52.4599307911,609.6 -1.818665969,52.4560915023,609.6 -1.8183695247,52.4522525448,609.6 -1.8174946675,52.448446667,609.6 -1.8160490067,52.4447063266,609.6 -1.8140450112,52.4410634144,609.6 -1.8114998987,52.4375489828,609.6 -1.8084354845,52.4341929817,609.6 -1.8048779924,52.4310240045,609.6 -1.8008578279,52.4280690449,609.6 -1.7964093168,52.4253532687,609.6 -1.7915704121,52.4228998002,609.6 -1.7863823696,52.4207295265,609.6 -1.7808893971,52.4188609209,609.6 -1.7751382792,52.417309887,609.6 -1.7691779807,52.4160896238,609.6 -1.7630592323,52.4152105147,609.6 -1.756834102,52.4146800394,609.6 -1.7505555556,52.4145027115,609.6 -1.7442770091,52.4146800394,609.6 -1.7380518788,52.4152105147,609.6 -1.7319331305,52.4160896238,609.6 -1.7259728319,52.417309887,609.6 -1.720221714,52.4188609209,609.6 -1.7147287415,52.4207295265,609.6 -1.709540699,52.4228998002,609.6 -1.7047017943,52.4253532687,609.6 -1.7002532833,52.4280690449,609.6 -1.6962331187,52.4310240045,609.6 -1.6926756266,52.4341929817,609.6 -1.6896112124,52.4375489828,609.6 -1.6870660999,52.4410634144,609.6 -1.6850621044,52.4447063266,609.6 -1.6836164436,52.448446667,609.6 -1.6827415864,52.4522525448,609.6 -1.6824451421,52.4560915023,609.6 -1.6827297903,52.4599307911,609.6 -1.6835932529,52.4637376518,609.6 -1.685028309,52.467479593,609.6 -1.6870228506,52.4711246695,609.6 -1.689559982,52.4746417551,609.6 -1.6926181596,52.4780008096,609.6 -1.6961713722,52.4811731357,609.6 -1.7001893599,52.4841316255,609.6 -1.704637871,52.4868509931,609.6 -1.7094789525,52.4893079919,609.6 -1.7146712746,52.4914816145,609.6 -1.7201704835,52.4933532735,609.6 -1.7259295825,52.4949069615,609.6 -1.731899335,52.496129389,609.6 -1.7380286881,52.4970100989,609.6 -1.7442652129,52.497541557,609.6 -1.7505555556,52.4977192163,609.6 + + + + + + EGRU210B BIRMINGHAM RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7507" txt_name="BIRMINGHAM RWY 15"><tr><td>522953N 0014822W -<br/>523011N 0014738W -<br/>522934N 0014657W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to<br/>522916N 0014741W -<br/>522953N 0014822W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8062,52.4981111111,609.6 -1.7947085,52.48780075,609.6 -1.7908524655,52.4896625365,609.6 -1.7867862897,52.4913496605,609.6 -1.7825311667,52.4928533333,609.6 -1.7940166667,52.5031611111,609.6 -1.8062,52.4981111111,609.6 + + + + + + EGRU210C BIRMINGHAM RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7958" txt_name="BIRMINGHAM RWY 33"><tr><td>522442N 0014132W -<br/>522424N 0014216W -<br/>522510N 0014307W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to<br/>522528N 0014223W -<br/>522442N 0014132W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6922444444,52.4116166667,609.6 -1.7064432222,52.4244166667,609.6 -1.7102953441,52.4225567709,609.6 -1.7143564184,52.4208713218,609.6 -1.7186053333,52.4193690556,609.6 -1.7044,52.4065666667,609.6 -1.6922444444,52.4116166667,609.6 + + + + + + EGRU211A DERBY + <table border="1" cellpadding="1" cellspacing="0" row_id="7732" txt_name="DERBY"><tr><td>A circle, 2 NM radius, centred at 525135N 0013703W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6175,52.8930064498,609.6 -1.6231586924,52.892829905,609.6 -1.6287572645,52.8923021463,609.6 -1.6342362393,52.8914287806,609.6 -1.6395374187,52.8902190862,609.6 -1.6446045057,52.8886859133,609.6 -1.6493837057,52.886845547,609.6 -1.6538242998,52.884717533,609.6 -1.6578791853,52.8823244689,609.6 -1.6615053761,52.8796917631,609.6 -1.6646644585,52.8768473633,609.6 -1.6673229974,52.8738214592,609.6 -1.6694528885,52.8706461602,609.6 -1.6710316529,52.867355154,609.6 -1.6720426712,52.8639833481,609.6 -1.6724753548,52.860566499,609.6 -1.6723252526,52.8571408323,609.6 -1.6715940928,52.8537426589,609.6 -1.6702897581,52.8504079896,609.6 -1.6684261974,52.8471721543,609.6 -1.666023272,52.8440694281,609.6 -1.663106541,52.8411326689,609.6 -1.6597069867,52.8383929708,609.6 -1.6558606832,52.8358793358,609.6 -1.6516084125,52.8336183681,609.6 -1.6469952321,52.8316339936,609.6 -1.6420699977,52.8299472084,609.6 -1.6368848474,52.8285758576,609.6 -1.631494652,52.8275344477,609.6 -1.6259564376,52.8268339942,609.6 -1.620328785,52.8264819055,609.6 -1.614671215,52.8264819055,609.6 -1.6090435624,52.8268339942,609.6 -1.603505348,52.8275344477,609.6 -1.5981151526,52.8285758576,609.6 -1.5929300023,52.8299472084,609.6 -1.5880047679,52.8316339936,609.6 -1.5833915875,52.8336183681,609.6 -1.5791393168,52.8358793358,609.6 -1.5752930133,52.8383929708,609.6 -1.571893459,52.8411326689,609.6 -1.568976728,52.8440694281,609.6 -1.5665738026,52.8471721543,609.6 -1.5647102419,52.8504079896,609.6 -1.5634059072,52.8537426589,609.6 -1.5626747474,52.8571408323,609.6 -1.5625246452,52.860566499,609.6 -1.5629573288,52.8639833481,609.6 -1.5639683471,52.867355154,609.6 -1.5655471115,52.8706461602,609.6 -1.5676770026,52.8738214592,609.6 -1.5703355415,52.8768473633,609.6 -1.5734946239,52.8796917631,609.6 -1.5771208147,52.8823244689,609.6 -1.5811757002,52.884717533,609.6 -1.5856162943,52.886845547,609.6 -1.5903954943,52.8886859133,609.6 -1.5954625813,52.8902190862,609.6 -1.6007637607,52.8914287806,609.6 -1.6062427355,52.8923021463,609.6 -1.6118413076,52.892829905,609.6 -1.6175,52.8930064498,609.6 + + + + + + EGRU211B DERBY RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7970" txt_name="DERBY RWY 05"><tr><td>524927N 0014006W -<br/>524951N 0014042W -<br/>525024N 0013942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>525001N 0013905W -<br/>524927N 0014006W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6682780278,52.8241792222,609.6 -1.6514153333,52.8335263333,609.6 -1.6551790821,52.8354843292,609.6 -1.6586362529,52.8376398054,609.6 -1.6617586667,52.8399752222,609.6 -1.6782875556,52.8308118889,609.6 -1.6682780278,52.8241792222,609.6 + + + + + + EGRU211C DERBY RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7587" txt_name="DERBY RWY 23"><tr><td>525336N 0013355W -<br/>525312N 0013319W -<br/>525240N 0013417W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>525305N 0013452W -<br/>525336N 0013355W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5653483889,52.8933006111,609.6 -1.5810313611,52.8846404444,609.6 -1.5774659925,52.8825482362,609.6 -1.5742274102,52.8802699556,609.6 -1.571342,52.8778241944,609.6 -1.5553245,52.886668,609.6 -1.5653483889,52.8933006111,609.6 + + + + + + EGRU211D DERBY RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7830" txt_name="DERBY RWY 10"><tr><td>525144N 0014134W -<br/>525216N 0014126W -<br/>525210N 0014012W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>525138N 0014021W -<br/>525144N 0014134W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6926618056,52.8621813611,609.6 -1.6724770556,52.8605240556,609.6 -1.6721355166,52.8635213229,609.6 -1.6713486888,52.866487734,609.6 -1.6701229167,52.8693991111,609.6 -1.6906521111,52.8710847222,609.6 -1.6926618056,52.8621813611,609.6 + + + + + + EGRU211E DERBY RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7768" txt_name="DERBY RWY 28"><tr><td>525131N 0013225W -<br/>525059N 0013233W -<br/>525106N 0013351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>525138N 0013345W -<br/>525131N 0013225W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5403897778,52.8586619444,609.6 -1.5625221667,52.8605040833,609.6 -1.5626315478,52.857500432,609.6 -1.5631879018,52.8545149834,609.6 -1.5641866111,52.8515720556,609.6 -1.5423988889,52.8497585556,609.6 -1.5403897778,52.8586619444,609.6 + + + + + + EGRU211F DERBY RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7670" txt_name="DERBY RWY 17"><tr><td>525422N 0013812W -<br/>525427N 0013720W -<br/>525335N 0013706W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>525330N 0013759W -<br/>525422N 0013812W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.63679225,52.9061841944,609.6 -1.6331029167,52.8916396667,609.6 -1.6282821584,52.8923609231,609.6 -1.6233734078,52.8928162187,609.6 -1.6184167222,52.8930018333,609.6 -1.6221006389,52.9075444444,609.6 -1.63679225,52.9061841944,609.6 + + + + + + EGRU211G DERBY RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7562" txt_name="DERBY RWY 35"><tr><td>524849N 0013554W -<br/>524844N 0013647W -<br/>524935N 0013700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to<br/>524940N 0013607W -<br/>524849N 0013554W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5983614722,52.8136583611,609.6 -1.6019306944,52.8278006389,609.6 -1.6067449988,52.8270810369,609.6 -1.6116466805,52.8266270276,609.6 -1.6165959167,52.8264423056,609.6 -1.6130214167,52.8122980833,609.6 -1.5983614722,52.8136583611,609.6 + + + + + + EGRU212A WELLESBOURNE MOUNTFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="8032" txt_name="WELLESBOURNE MOUNTFORD"><tr><td>A circle, 2 NM radius, centred at 521132N 0013652W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6144,52.2254963366,609.6 -1.6199734531,52.225319775,609.6 -1.6254876949,52.2247919659,609.6 -1.6308841471,52.2239185166,609.6 -1.636105491,52.2227087055,609.6 -1.64109628,52.2211753837,609.6 -1.6458035312,52.2193348369,609.6 -1.6501772909,52.2172066119,609.6 -1.6541711659,52.2148133076,609.6 -1.6577428169,52.2121803337,609.6 -1.6608544075,52.2093356402,609.6 -1.663473004,52.2063094187,609.6 -1.6655709225,52.2031337812,609.6 -1.6671260192,52.1998424183,609.6 -1.6681219212,52.1964702408,609.6 -1.6685481951,52.1930530088,609.6 -1.6684004526,52.1896269519,609.6 -1.6676803914,52.1862283849,609.6 -1.6663957719,52.1828933233,609.6 -1.6645603288,52.1796571014,609.6 -1.6621936216,52.1765539991,609.6 -1.659320822,52.1736168792,609.6 -1.6559724441,52.1708768403,609.6 -1.652184018,52.168362889,609.6 -1.6479957121,52.1661016338,609.6 -1.6434519062,52.1641170047,609.6 -1.6386007224,52.1624300014,609.6 -1.6334935167,52.1610584721,609.6 -1.6281843373,52.160016926,609.6 -1.6227293555,52.1593163805,609.6 -1.617186275,52.1589642455,609.6 -1.611613725,52.1589642455,609.6 -1.6060706445,52.1593163805,609.6 -1.6006156627,52.160016926,609.6 -1.5953064833,52.1610584721,609.6 -1.5901992776,52.1624300014,609.6 -1.5853480938,52.1641170047,609.6 -1.5808042879,52.1661016338,609.6 -1.576615982,52.168362889,609.6 -1.5728275559,52.1708768403,609.6 -1.569479178,52.1736168792,609.6 -1.5666063784,52.1765539991,609.6 -1.5642396712,52.1796571014,609.6 -1.5624042281,52.1828933233,609.6 -1.5611196086,52.1862283849,609.6 -1.5603995474,52.1896269519,609.6 -1.5602518049,52.1930530088,609.6 -1.5606780788,52.1964702408,609.6 -1.5616739808,52.1998424183,609.6 -1.5632290775,52.2031337812,609.6 -1.565326996,52.2063094187,609.6 -1.5679455925,52.2093356402,609.6 -1.5710571831,52.2121803337,609.6 -1.5746288341,52.2148133076,609.6 -1.5786227091,52.2172066119,609.6 -1.5829964688,52.2193348369,609.6 -1.58770372,52.2211753837,609.6 -1.592694509,52.2227087055,609.6 -1.5979158529,52.2239185166,609.6 -1.6033123051,52.2247919659,609.6 -1.6088265469,52.225319775,609.6 -1.6144,52.2254963366,609.6 + + + + + + EGRU212B WELLESBOURNE MOUNTFORD RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7633" txt_name="WELLESBOURNE MOUNTFORD RWY 05"><tr><td>520909N 0013952W -<br/>520932N 0014029W -<br/>521014N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to<br/>520952N 0013840W -<br/>520909N 0013952W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6644833333,52.1525,609.6 -1.6445776111,52.1645690833,609.6 -1.6485160735,52.1663578639,609.6 -1.6521759225,52.1683580392,609.6 -1.6555272222,52.1705532778,609.6 -1.6747361111,52.1589055556,609.6 -1.6644833333,52.1525,609.6 + + + + + + EGRU212C WELLESBOURNE MOUNTFORD RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7947" txt_name="WELLESBOURNE MOUNTFORD RWY 23"><tr><td>521332N 0013352W -<br/>521309N 0013315W -<br/>521237N 0013408W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to<br/>521302N 0013443W -<br/>521332N 0013352W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5644666667,52.2256444444,609.6 -1.5785241667,52.2171532222,609.6 -1.5750030605,52.2150594228,609.6 -1.5718046369,52.2127787035,609.6 -1.5689550278,52.21032975,609.6 -1.5542,52.2192416667,609.6 -1.5644666667,52.2256444444,609.6 + + + + + + EGRU212D WELLESBOURNE MOUNTFORD RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="8102" txt_name="WELLESBOURNE MOUNTFORD RWY 18"><tr><td>521427N 0013738W -<br/>521429N 0013645W -<br/>521332N 0013639W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to<br/>521329N 0013731W -<br/>521427N 0013738W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6271083333,52.240825,609.6 -1.6253352222,52.2248114167,609.6 -1.6205050805,52.2252843723,609.6 -1.6156251224,52.2254878269,609.6 -1.6107351667,52.2254201111,609.6 -1.6125027778,52.2414333333,609.6 -1.6271083333,52.240825,609.6 + + + + + + EGRU212E WELLESBOURNE MOUNTFORD RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7877" txt_name="WELLESBOURNE MOUNTFORD RWY 36"><tr><td>520837N 0013606W -<br/>520835N 0013659W -<br/>520932N 0013705W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to<br/>520935N 0013613W -<br/>520837N 0013606W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6017222222,52.1435888889,609.6 -1.6034835,52.1596037222,609.6 -1.6083064442,52.1591316218,609.6 -1.6131788875,52.1589286094,609.6 -1.61806125,52.1589963333,609.6 -1.6162944444,52.1429805556,609.6 -1.6017222222,52.1435888889,609.6 + + + + + + EGRU213A COVENTRY + <table border="1" cellpadding="1" cellspacing="0" row_id="8132" txt_name="COVENTRY"><tr><td>A circle, 2.5 NM radius, centred at 522211N 0012847W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4796805556,52.4114198271,609.6 -1.4859586139,52.4112421657,609.6 -1.4921829598,52.4107107014,609.6 -1.4983003443,52.409829981,609.6 -1.5042584412,52.408607539,609.6 -1.5100062976,52.4070538323,609.6 -1.5154947736,52.4051821507,609.6 -1.520676964,52.4030085014,609.6 -1.5255086022,52.4005514721,609.6 -1.5299484387,52.3978320702,609.6 -1.5339585949,52.3948735425,609.6 -1.5375048854,52.3917011751,609.6 -1.5405571093,52.388342076,609.6 -1.5430893058,52.3848249429,609.6 -1.5450799728,52.3811798163,609.6 -1.5465122469,52.3774378227,609.6 -1.5473740435,52.3736309076,609.6 -1.5476581549,52.3697915629,609.6 -1.5473623069,52.3659525485,609.6 -1.5464891734,52.3621466133,609.6 -1.545046348,52.3584062155,609.6 -1.5430462749,52.3547632464,609.6 -1.5405061376,52.351248759,609.6 -1.5374477087,52.3478927039,609.6 -1.5338971602,52.3447236748,609.6 -1.5298848382,52.3417686664,609.6 -1.5254450017,52.3390528447,609.6 -1.5206155294,52.3365993346,609.6 -1.5154375968,52.3344290237,609.6 -1.5099553259,52.332560386,609.6 -1.5042154102,52.3310093251,609.6 -1.4982667195,52.3297890406,609.6 -1.4921598862,52.3289099161,609.6 -1.4859468772,52.3283794315,609.6 -1.4796805556,52.3282021004,609.6 -1.4734142339,52.3283794315,609.6 -1.4672012249,52.3289099161,609.6 -1.4610943916,52.3297890406,609.6 -1.4551457009,52.3310093251,609.6 -1.4494057852,52.332560386,609.6 -1.4439235143,52.3344290237,609.6 -1.4387455817,52.3365993346,609.6 -1.4339161094,52.3390528447,609.6 -1.4294762729,52.3417686664,609.6 -1.4254639509,52.3447236748,609.6 -1.4219134024,52.3478927039,609.6 -1.4188549735,52.351248759,609.6 -1.4163148362,52.3547632464,609.6 -1.4143147631,52.3584062155,609.6 -1.4128719377,52.3621466133,609.6 -1.4119988042,52.3659525485,609.6 -1.4117029562,52.3697915629,609.6 -1.4119870676,52.3736309076,609.6 -1.4128488642,52.3774378227,609.6 -1.4142811383,52.3811798163,609.6 -1.4162718053,52.3848249429,609.6 -1.4188040018,52.388342076,609.6 -1.4218562257,52.3917011751,609.6 -1.4254025162,52.3948735425,609.6 -1.4294126724,52.3978320702,609.6 -1.4338525089,52.4005514721,609.6 -1.4386841471,52.4030085014,609.6 -1.4438663375,52.4051821507,609.6 -1.4493548135,52.4070538323,609.6 -1.4551026699,52.408607539,609.6 -1.4610607668,52.409829981,609.6 -1.4671781513,52.4107107014,609.6 -1.4734024973,52.4112421657,609.6 -1.4796805556,52.4114198271,609.6 + + + + + + EGRU213B COVENTRY RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8013" txt_name="COVENTRY RWY 05"><tr><td>521952N 0013215W -<br/>522016N 0013250W -<br/>522042N 0013204W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to<br/>522019N 0013128W -<br/>521952N 0013215W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5373944444,52.3311361111,609.6 -1.52439425,52.3384789444,609.6 -1.5279657452,52.3405328775,609.6 -1.5312866019,52.3427390404,609.6 -1.5343395556,52.3450859722,609.6 -1.5473305556,52.3377472222,609.6 -1.5373944444,52.3311361111,609.6 + + + + + + EGRU213C COVENTRY RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="8089" txt_name="COVENTRY RWY 23"><tr><td>522430N 0012519W -<br/>522407N 0012443W -<br/>522340N 0012530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to<br/>522404N 0012606W -<br/>522430N 0012519W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4218777778,52.4084555556,609.6 -1.4349076111,52.4011283611,609.6 -1.4313348092,52.3990715077,609.6 -1.4280140169,52.3968623818,609.6 -1.4249625,52.3945125,609.6 -1.4119222222,52.4018444444,609.6 -1.4218777778,52.4084555556,609.6 + + + + + + EGRU214A EAST MIDLANDS + <table border="1" cellpadding="1" cellspacing="0" row_id="7554" txt_name="EAST MIDLANDS"><tr><td>A circle, 2.5 NM radius, centred at 524952N 0011940W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3277777778,52.8727165679,609.6 -1.3341222329,52.8725389176,609.6 -1.3404124051,52.8720074866,609.6 -1.3465944797,52.8711268217,609.6 -1.3526155747,52.8699044571,609.6 -1.3584241967,52.8683508497,609.6 -1.3639706843,52.8664792888,609.6 -1.3692076354,52.8643057815,609.6 -1.3740903145,52.8618489148,609.6 -1.3785770361,52.8591296956,609.6 -1.3826295214,52.8561713699,609.6 -1.3862132249,52.8529992227,609.6 -1.3892976278,52.849640361,609.6 -1.391856497,52.846123481,609.6 -1.3938681056,52.8424786217,609.6 -1.3953154151,52.8387369078,609.6 -1.3961862161,52.8349302827,609.6 -1.396473228,52.8310912361,609.6 -1.3961741563,52.8272525253,609.6 -1.3952917062,52.8234468966,609.6 -1.393833555,52.8197068054,609.6 -1.3918122811,52.8160641401,609.6 -1.3892452525,52.8125499505,609.6 -1.3861544737,52.8091941841,609.6 -1.3825663951,52.8060254317,609.6 -1.3785116842,52.8030706845,609.6 -1.3740249626,52.8003551059,609.6 -1.369144509,52.7979018179,609.6 -1.363911933,52.7957317053,609.6 -1.3583718213,52.7938632398,609.6 -1.3525713588,52.7923123228,609.6 -1.3465599289,52.7910921522,609.6 -1.3403886961,52.79021311,609.6 -1.3341101731,52.7896826753,609.6 -1.3277777778,52.7895053609,609.6 -1.3214453824,52.7896826753,609.6 -1.3151668594,52.79021311,609.6 -1.3089956266,52.7910921522,609.6 -1.3029841968,52.7923123228,609.6 -1.2971837343,52.7938632398,609.6 -1.2916436225,52.7957317053,609.6 -1.2864110466,52.7979018179,609.6 -1.2815305929,52.8003551059,609.6 -1.2770438713,52.8030706845,609.6 -1.2729891605,52.8060254317,609.6 -1.2694010819,52.8091941841,609.6 -1.2663103031,52.8125499505,609.6 -1.2637432744,52.8160641401,609.6 -1.2617220006,52.8197068054,609.6 -1.2602638494,52.8234468966,609.6 -1.2593813993,52.8272525253,609.6 -1.2590823275,52.8310912361,609.6 -1.2593693395,52.8349302827,609.6 -1.2602401405,52.8387369078,609.6 -1.2616874499,52.8424786217,609.6 -1.2636990586,52.846123481,609.6 -1.2662579278,52.849640361,609.6 -1.2693423307,52.8529992227,609.6 -1.2729260341,52.8561713699,609.6 -1.2769785194,52.8591296956,609.6 -1.2814652411,52.8618489148,609.6 -1.2863479202,52.8643057815,609.6 -1.2915848713,52.8664792888,609.6 -1.2971313589,52.8683508497,609.6 -1.3029399809,52.8699044571,609.6 -1.3089610759,52.8711268217,609.6 -1.3151431504,52.8720074866,609.6 -1.3214333226,52.8725389176,609.6 -1.3277777778,52.8727165679,609.6 + + + + + + EGRU214B EAST MIDLANDS RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8040" txt_name="EAST MIDLANDS RWY 09"><tr><td>524929N 0012515W -<br/>525002N 0012517W -<br/>525003N 0012347W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to<br/>524931N 0012345W -<br/>524929N 0012515W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4208305556,52.824775,609.6 -1.3957835,52.8252495278,609.6 -1.3963064082,52.8282329641,609.6 -1.3964730465,52.8312314664,609.6 -1.3962824722,52.8342294444,609.6 -1.421275,52.8337555556,609.6 -1.4208305556,52.824775,609.6 + + + + + + EGRU214C EAST MIDLANDS RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="8095" txt_name="EAST MIDLANDS RWY 27"><tr><td>525014N 0011405W -<br/>524941N 0011403W -<br/>524940N 0011534W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to<br/>525012N 0011535W -<br/>525014N 0011405W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2346666667,52.8371666667,609.6 -1.2597063611,52.8367260278,609.6 -1.2592174925,52.8337397508,609.6 -1.2590853456,52.8307399007,609.6 -1.2593105556,52.8277420833,609.6 -1.2342138889,52.8281833333,609.6 -1.2346666667,52.8371666667,609.6 + + + + + + EGRU215A NOTTINGHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="8125" txt_name="NOTTINGHAM"><tr><td>A circle, 2 NM radius, centred at 525515N 0010448W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.08,52.9541172165,609.6 -1.0856666656,52.9539406732,609.6 -1.0912731259,52.9534129191,609.6 -1.0967598197,52.952539561,609.6 -1.1020684668,52.9513298772,609.6 -1.1071426907,52.9497967178,609.6 -1.1119286206,52.9479563679,609.6 -1.1163754663,52.9458283731,609.6 -1.1204360586,52.9434353309,609.6 -1.1240673509,52.9408026494,609.6 -1.1272308755,52.9379582765,609.6 -1.1298931505,52.9349324012,609.6 -1.1320260322,52.9317571331,609.6 -1.1336070103,52.9284661594,609.6 -1.1346194424,52.9250943874,609.6 -1.1350527254,52.9216775732,609.6 -1.1349024025,52.9182519421,609.6 -1.1341702043,52.9148538046,609.6 -1.1328640255,52.9115191711,609.6 -1.1309978346,52.9082833711,609.6 -1.1285915213,52.9051806792,609.6 -1.1256706811,52.902243953,609.6 -1.1222663398,52.8995042861,609.6 -1.1184146226,52.89699068,609.6 -1.1141563688,52.8947297385,609.6 -1.1095366993,52.8927453873,609.6 -1.1046045384,52.8910586221,609.6 -1.0994120974,52.8896872876,609.6 -1.0940143241,52.8886458902,609.6 -1.0884683244,52.8879454451,609.6 -1.0828327612,52.8875933606,609.6 -1.0771672388,52.8875933606,609.6 -1.0715316756,52.8879454451,609.6 -1.0659856759,52.8886458902,609.6 -1.0605879026,52.8896872876,609.6 -1.0553954616,52.8910586221,609.6 -1.0504633007,52.8927453873,609.6 -1.0458436312,52.8947297385,609.6 -1.0415853774,52.89699068,609.6 -1.0377336602,52.8995042861,609.6 -1.0343293189,52.902243953,609.6 -1.0314084787,52.9051806792,609.6 -1.0290021654,52.9082833711,609.6 -1.0271359745,52.9115191711,609.6 -1.0258297957,52.9148538046,609.6 -1.0250975975,52.9182519421,609.6 -1.0249472746,52.9216775732,609.6 -1.0253805576,52.9250943874,609.6 -1.0263929897,52.9284661594,609.6 -1.0279739678,52.9317571331,609.6 -1.0301068495,52.9349324012,609.6 -1.0327691245,52.9379582765,609.6 -1.0359326491,52.9408026494,609.6 -1.0395639414,52.9434353309,609.6 -1.0436245337,52.9458283731,609.6 -1.0480713794,52.9479563679,609.6 -1.0528573093,52.9497967178,609.6 -1.0579315332,52.9513298772,609.6 -1.0632401803,52.952539561,609.6 -1.0687268741,52.9534129191,609.6 -1.0743333344,52.9539406732,609.6 -1.08,52.9541172165,609.6 + + + + + + EGRU215B NOTTINGHAM RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7888" txt_name="NOTTINGHAM RWY 03"><tr><td>525228N 0010627W -<br/>525244N 0010715W -<br/>525333N 0010632W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to<br/>525320N 0010542W -<br/>525228N 0010627W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1075944444,52.8745638889,609.6 -1.09513225,52.8888314444,609.6 -1.0998531952,52.8897890795,609.6 -1.1044119397,52.8910007221,609.6 -1.1087712222,52.8924564722,609.6 -1.120725,52.8787666667,609.6 -1.1075944444,52.8745638889,609.6 + + + + + + EGRU215C NOTTINGHAM RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7641" txt_name="NOTTINGHAM RWY 21"><tr><td>525754N 0010243W -<br/>525738N 0010156W -<br/>525647N 0010241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to<br/>525704N 0010327W -<br/>525754N 0010243W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0454,52.9648666667,609.6 -1.0573920833,52.9511852778,609.6 -1.0529431955,52.9498260518,609.6 -1.0487162267,52.9482293672,609.6 -1.0447458056,52.9464083333,609.6 -1.0322444444,52.9606666667,609.6 -1.0454,52.9648666667,609.6 + + + + + + EGRU215D NOTTINGHAM RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7595" txt_name="NOTTINGHAM RWY 09"><tr><td>525452N 0010933W -<br/>525524N 0010935W -<br/>525526N 0010805W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to<br/>525454N 0010803W -<br/>525452N 0010933W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1592722222,52.9143111111,609.6 -1.1341868056,52.9149089167,609.6 -1.1348516491,52.9178856696,609.6 -1.1350698583,52.9208865282,609.6 -1.1348395556,52.9238870556,609.6 -1.1598416667,52.9232916667,609.6 -1.1592722222,52.9143111111,609.6 + + + + + + EGRU215E NOTTINGHAM RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7660" txt_name="NOTTINGHAM RWY 27"><tr><td>525537N 0005958W -<br/>525505N 0005956W -<br/>525503N 0010131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to<br/>525535N 0010133W -<br/>525537N 0005958W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9993333333,52.9270222222,609.6 -1.0257090556,52.9264241111,609.6 -1.0250980782,52.9234437562,609.6 -1.0249341478,52.9204422491,609.6 -1.0252185,52.9174440278,609.6 -0.9987611111,52.9180444444,609.6 -0.9993333333,52.9270222222,609.6 + + + + + + EGRU216A LEICESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="7883" txt_name="LEICESTER"><tr><td>A circle, 2 NM radius, centred at 523628N 0010155W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0319444444,52.6410634276,609.6 -1.0375705691,52.6408868765,609.6 -1.0431369207,52.6403590989,609.6 -1.0485843657,52.6394857017,609.6 -1.053855042,52.6382759635,609.6 -1.0588929776,52.6367427346,609.6 -1.0636446878,52.6349023004,609.6 -1.0680597463,52.6327742071,609.6 -1.0720913215,52.6303810526,609.6 -1.0756966742,52.627748246,609.6 -1.0788376114,52.6249037357,609.6 -1.0814808896,52.6218777121,609.6 -1.0835985651,52.6187022857,609.6 -1.085168287,52.6154111452,609.6 -1.08617353,52.6120391994,609.6 -1.0866037648,52.608622206,609.6 -1.0864545645,52.6051963924,609.6 -1.0857276454,52.6017980707,609.6 -1.0844308436,52.5984632535,609.6 -1.082578026,52.5952272725,609.6 -1.0801889387,52.5921244045,609.6 -1.0772889928,52.5891875093,609.6 -1.0739089916,52.5864476827,609.6 -1.0700848014,52.5839339285,609.6 -1.0658569699,52.5816728523,609.6 -1.0612702954,52.5796883817,609.6 -1.0563733535,52.5780015143,609.6 -1.0512179835,52.5766300961,609.6 -1.0458587418,52.5755886349,609.6 -1.0403523279,52.5748881467,609.6 -1.0347569877,52.5745360405,609.6 -1.0291319012,52.5745360405,609.6 -1.023536561,52.5748881467,609.6 -1.0180301471,52.5755886349,609.6 -1.0126709054,52.5766300961,609.6 -1.0075155354,52.5780015143,609.6 -1.0026185935,52.5796883817,609.6 -0.998031919,52.5816728523,609.6 -0.9938040874,52.5839339285,609.6 -0.9899798973,52.5864476827,609.6 -0.9865998961,52.5891875093,609.6 -0.9836999502,52.5921244045,609.6 -0.9813108629,52.5952272725,609.6 -0.9794580453,52.5984632535,609.6 -0.9781612435,52.6017980707,609.6 -0.9774343244,52.6051963924,609.6 -0.9772851241,52.608622206,609.6 -0.9777153589,52.6120391994,609.6 -0.9787206019,52.6154111452,609.6 -0.9802903238,52.6187022857,609.6 -0.9824079993,52.6218777121,609.6 -0.9850512774,52.6249037357,609.6 -0.9881922147,52.627748246,609.6 -0.9917975674,52.6303810526,609.6 -0.9958291425,52.6327742071,609.6 -1.000244201,52.6349023004,609.6 -1.0049959113,52.6367427346,609.6 -1.0100338469,52.6382759635,609.6 -1.0153045232,52.6394857017,609.6 -1.0207519682,52.6403590989,609.6 -1.0263183198,52.6408868765,609.6 -1.0319444444,52.6410634276,609.6 + + + + + + EGRU216B LEICESTER RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="8177" txt_name="LEICESTER RWY 04"><tr><td>523354N 0010406W -<br/>523413N 0010448W -<br/>523454N 0010358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523438N 0010312W -<br/>523354N 0010406W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0683138889,52.56495,609.6 -1.0533300833,52.5771455833,609.6 -1.0578004505,52.5784517699,609.6 -1.0620583556,52.5799992746,609.6 -1.0660687778,52.5817753889,609.6 -1.0801166667,52.5703388889,609.6 -1.0683138889,52.56495,609.6 + + + + + + EGRU216C LEICESTER RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7841" txt_name="LEICESTER RWY 22"><tr><td>523845N 0005914W -<br/>523826N 0005831W -<br/>523744N 0005923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523806N 0010002W -<br/>523845N 0005914W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9871722222,52.6458638889,609.6 -1.0005339722,52.6350268889,609.6 -0.9966043647,52.6331813756,609.6 -0.9929662177,52.6311266371,609.6 -0.9896495,52.6288796111,609.6 -0.97535,52.640475,609.6 -0.9871722222,52.6458638889,609.6 + + + + + + EGRU216D LEICESTER RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7563" txt_name="LEICESTER RWY 06"><tr><td>523417N 0010449W -<br/>523441N 0010525W -<br/>523513N 0010428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523450N 0010349W -<br/>523417N 0010449W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0803583333,52.5713138889,609.6 -1.0636405833,52.5806598333,609.6 -1.0675359805,52.5825151294,609.6 -1.0711404251,52.5845772236,609.6 -1.0744244167,52.58682925,609.6 -1.090325,52.5779388889,609.6 -1.0803583333,52.5713138889,609.6 + + + + + + EGRU216E LEICESTER RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7812" txt_name="LEICESTER RWY 24"><tr><td>523827N 0005840W -<br/>523803N 0005804W -<br/>523729N 0005905W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523754N 0005938W -<br/>523827N 0005840W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9776805556,52.6407972222,609.6 -0.99396425,52.6317283056,609.6 -0.9905625572,52.6295401098,609.6 -0.9875002128,52.6271736895,609.6 -0.9848022778,52.6246484444,609.6 -0.9677,52.6341722222,609.6 -0.9776805556,52.6407972222,609.6 + + + + + + EGRU216F LEICESTER RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="8071" txt_name="LEICESTER RWY 10"><tr><td>523631N 0010647W -<br/>523703N 0010641W -<br/>523657N 0010506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523625N 0010512W -<br/>523631N 0010647W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1130722222,52.6085833333,609.6 -1.0866007222,52.6068874444,609.6 -1.0865119041,52.6098905627,609.6 -1.0859786876,52.6128765769,609.6 -1.0850053333,52.6158211667,609.6 -1.1115138889,52.6175194444,609.6 -1.1130722222,52.6085833333,609.6 + + + + + + EGRU216G LEICESTER RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7870" txt_name="LEICESTER RWY 28"><tr><td>523626N 0005704W -<br/>523554N 0005709W -<br/>523600N 0005844W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523632N 0005838W -<br/>523626N 0005704W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.950975,52.6071416667,609.6 -0.9772961944,52.6088584167,609.6 -0.9773605349,52.6058550628,609.6 -0.9778692787,52.6028674649,609.6 -0.9788181944,52.5999199444,609.6 -0.9525333333,52.5982055556,609.6 -0.950975,52.6071416667,609.6 + + + + + + EGRU216H LEICESTER RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7850" txt_name="LEICESTER RWY 15"><tr><td>523841N 0010436W -<br/>523857N 0010350W -<br/>523818N 0010314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523801N 0010359W -<br/>523841N 0010436W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.076675,52.644675,609.6 -1.0663972778,52.6336289722,609.6 -1.0624252862,52.6354151885,609.6 -1.0582044025,52.6369760432,609.6 -1.0537690556,52.6382987778,609.6 -1.0638138889,52.6490972222,609.6 -1.076675,52.644675,609.6 + + + + + + EGRU216I LEICESTER RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7761" txt_name="LEICESTER RWY 33"><tr><td>523401N 0005915W -<br/>523345N 0010001W -<br/>523435N 0010048W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523450N 0010001W -<br/>523401N 0005915W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9875722222,52.5669805556,609.6 -1.0002493889,52.5806593611,609.6 -1.0043947656,52.5790293299,609.6 -1.0087643261,52.5776335702,609.6 -1.0133225,52.5764834444,609.6 -1.0004111111,52.5625555556,609.6 -0.9875722222,52.5669805556,609.6 + + + + + + EGRU216J LEICESTER RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="7591" txt_name="LEICESTER RWY 16"><tr><td>523837N 0010440W -<br/>523854N 0010355W -<br/>523817N 0010318W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523759N 0010403W -<br/>523837N 0010440W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0777805556,52.6435361111,609.6 -1.0673638056,52.6331404444,609.6 -1.0634615593,52.6349812391,609.6 -1.059302093,52.6366003276,609.6 -1.0549193333,52.6379845,609.6 -1.0651611111,52.6482083333,609.6 -1.0777805556,52.6435361111,609.6 + + + + + + EGRU216K LEICESTER RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="7794" txt_name="LEICESTER RWY 34"><tr><td>523405N 0005906W -<br/>523348N 0005952W -<br/>523437N 0010040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to<br/>523453N 0005954W -<br/>523405N 0005906W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9850805556,52.5681166667,609.6 -0.9984237778,52.5814858611,609.6 -1.0024525214,52.5797529201,609.6 -1.00672106,52.5782481656,609.6 -1.0111946667,52.5769838333,609.6 -0.9976777778,52.5634444444,609.6 -0.9850805556,52.5681166667,609.6 + + + + + + EGRU217A NORTHAMPTON/SYWELL + <table border="1" cellpadding="1" cellspacing="0" row_id="7657" txt_name="NORTHAMPTON/SYWELL"><tr><td>A circle, 2 NM radius, centred at 521822N 0004732W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7922222222,52.3393984685,609.6 -0.7978099841,52.3392219097,609.6 -0.8033383821,52.3386941093,609.6 -0.8087486871,52.3378206743,609.6 -0.8139834327,52.3366108832,609.6 -0.8189870296,52.335077587,609.6 -0.8237063586,52.3332370711,609.6 -0.8280913376,52.3311088823,609.6 -0.8320954543,52.3287156191,609.6 -0.8356762609,52.3260826912,609.6 -0.8387958239,52.323238048,609.6 -0.8414211255,52.3202118809,609.6 -0.8435244113,52.3170363014,609.6 -0.8450834812,52.3137449995,609.6 -0.8460819208,52.3103728857,609.6 -0.8465092708,52.3069557192,609.6 -0.8463611324,52.303529729,609.6 -0.8456392083,52.3001312293,609.6 -0.8443512793,52.2967962348,609.6 -0.8425111163,52.293560079,609.6 -0.8401383293,52.290457041,609.6 -0.8372581551,52.2875199827,609.6 -0.8339011864,52.284780002,609.6 -0.8301030446,52.2822661048,609.6 -0.825904001,52.2800048986,609.6 -0.8213485493,52.278020313,609.6 -0.8164849347,52.2763333469,609.6 -0.8113646445,52.2749618482,609.6 -0.806041865,52.2739203253,609.6 -0.800572911,52.2732197955,609.6 -0.7950156334,52.2728676684,609.6 -0.7894288111,52.2728676684,609.6 -0.7838715335,52.2732197955,609.6 -0.7784025794,52.2739203253,609.6 -0.7730797999,52.2749618482,609.6 -0.7679595097,52.2763333469,609.6 -0.7630958952,52.278020313,609.6 -0.7585404435,52.2800048986,609.6 -0.7543413999,52.2822661048,609.6 -0.7505432581,52.284780002,609.6 -0.7471862893,52.2875199827,609.6 -0.7443061151,52.290457041,609.6 -0.7419333281,52.293560079,609.6 -0.7400931651,52.2967962348,609.6 -0.7388052362,52.3001312293,609.6 -0.7380833121,52.303529729,609.6 -0.7379351736,52.3069557192,609.6 -0.7383625236,52.3103728857,609.6 -0.7393609633,52.3137449995,609.6 -0.7409200331,52.3170363014,609.6 -0.7430233189,52.3202118809,609.6 -0.7456486206,52.323238048,609.6 -0.7487681836,52.3260826912,609.6 -0.7523489901,52.3287156191,609.6 -0.7563531068,52.3311088823,609.6 -0.7607380858,52.3332370711,609.6 -0.7654574149,52.335077587,609.6 -0.7704610118,52.3366108832,609.6 -0.7756957574,52.3378206743,609.6 -0.7811060623,52.3386941093,609.6 -0.7866344603,52.3392219097,609.6 -0.7922222222,52.3393984685,609.6 + + + + + + EGRU217B NORTHAMPTON/SYWELL RWY 03L + <table border="1" cellpadding="1" cellspacing="0" row_id="7569" txt_name="NORTHAMPTON/SYWELL RWY 03L"><tr><td>521535N 0004908W -<br/>521549N 0004956W -<br/>521641N 0004917W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521627N 0004829W -<br/>521535N 0004908W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8188444444,52.25975,609.6 -0.8080391111,52.2742679167,609.6 -0.812654855,52.2752715462,609.6 -0.8171045318,52.276526193,609.6 -0.8213519722,52.2780216389,609.6 -0.8321666667,52.2634861111,609.6 -0.8188444444,52.25975,609.6 + + + + + + EGRU217C NORTHAMPTON/SYWELL RWY 21R + <table border="1" cellpadding="1" cellspacing="0" row_id="8142" txt_name="NORTHAMPTON/SYWELL RWY 21R"><tr><td>522108N 0004558W -<br/>522054N 0004510W -<br/>522003N 0004548W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>522017N 0004636W -<br/>522108N 0004558W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7660416667,52.3521972222,609.6 -0.7766436667,52.3380003611,609.6 -0.7720147602,52.3370096914,609.6 -0.7675507069,52.3357673179,609.6 -0.7632879167,52.3342833611,609.6 -0.7526944444,52.3484638889,609.6 -0.7660416667,52.3521972222,609.6 + + + + + + EGRU217D NORTHAMPTON/SYWELL RWY 03R + <table border="1" cellpadding="1" cellspacing="0" row_id="8151" txt_name="NORTHAMPTON/SYWELL RWY 03R"><tr><td>521535N 0004902W -<br/>521548N 0004950W -<br/>521639N 0004912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521626N 0004824W -<br/>521535N 0004902W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.817225,52.2596388889,609.6 -0.8065377222,52.2740019167,609.6 -0.8112001893,52.2749240222,609.6 -0.8157083104,52.2761001429,609.6 -0.8200254167,52.2775206944,609.6 -0.8305472222,52.263375,609.6 -0.817225,52.2596388889,609.6 + + + + + + EGRU217E NORTHAMPTON/SYWELL RWY 21L + <table border="1" cellpadding="1" cellspacing="0" row_id="7808" txt_name="NORTHAMPTON/SYWELL RWY 21L"><tr><td>522102N 0004556W -<br/>522049N 0004508W -<br/>522002N 0004543W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>522016N 0004631W -<br/>522102N 0004556W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7655472222,52.3506027778,609.6 -0.77516825,52.3377156111,609.6 -0.7705856744,52.3366441745,609.6 -0.7661797483,52.3353238089,609.6 -0.7619864167,52.3337653056,609.6 -0.7522,52.3468694444,609.6 -0.7655472222,52.3506027778,609.6 + + + + + + EGRU217F NORTHAMPTON/SYWELL RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7977" txt_name="NORTHAMPTON/SYWELL RWY 05"><tr><td>521618N 0005049W -<br/>521643N 0005121W -<br/>521715N 0005014W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521651N 0004939W -<br/>521618N 0005049W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8469,52.2715333333,609.6 -0.8275625,52.2808424722,609.6 -0.8311402354,52.282902354,609.6 -0.834400312,52.2851519226,609.6 -0.8373160833,52.2875728056,609.6 -0.8559361111,52.2786083333,609.6 -0.8469,52.2715333333,609.6 + + + + + + EGRU217G NORTHAMPTON/SYWELL RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7804" txt_name="NORTHAMPTON/SYWELL RWY 23"><tr><td>522015N 0004401W -<br/>521949N 0004328W -<br/>521916N 0004437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521943N 0004507W -<br/>522015N 0004401W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7336,52.3373861111,609.6 -0.7520706944,52.3285297778,609.6 -0.7489313661,52.3262153965,609.6 -0.7461463395,52.3237366888,609.6 -0.7437383333,52.3211139444,609.6 -0.72455,52.3303138889,609.6 -0.7336,52.3373861111,609.6 + + + + + + EGRU217H NORTHAMPTON/SYWELL RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="7680" txt_name="NORTHAMPTON/SYWELL RWY 14"><tr><td>522016N 0005109W -<br/>522039N 0005032W -<br/>522000N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521938N 0005004W -<br/>522016N 0005109W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8524527778,52.3377472222,609.6 -0.8343298333,52.3271384167,609.6 -0.8310595854,52.3293832458,609.6 -0.8274715192,52.3314378811,609.6 -0.8235949444,52.3332855,609.6 -0.8423083333,52.3442416667,609.6 -0.8524527778,52.3377472222,609.6 + + + + + + EGRU217I NORTHAMPTON/SYWELL RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="8012" txt_name="NORTHAMPTON/SYWELL RWY 32"><tr><td>521638N 0004340W -<br/>521614N 0004417W -<br/>521653N 0004522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to<br/>521717N 0004448W -<br/>521638N 0004340W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.7279055556,52.2771305556,609.6 -0.7465651944,52.2880981667,609.6 -0.7494051076,52.2856446324,609.6 -0.7525943514,52.2833582938,609.6 -0.7561068611,52.2812578056,609.6 -0.7380333333,52.2706361111,609.6 -0.7279055556,52.2771305556,609.6 + + + + + + EGRU218A CRANFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="7930" txt_name="CRANFIELD"><tr><td>A circle, 2 NM radius, centred at 520420N 0003700W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6166666667,52.1055109067,609.6 -0.6222251498,52.105334342,609.6 -0.6277245811,52.1048065238,609.6 -0.6331065404,52.1039330593,609.6 -0.6383138633,52.1027232271,609.6 -0.6432912525,52.1011898783,609.6 -0.6479858678,52.0993492989,609.6 -0.6523478896,52.0972210357,609.6 -0.6563310496,52.0948276879,609.6 -0.659893122,52.0921946656,609.6 -0.6629963717,52.089349919,609.6 -0.6656079531,52.0863236401,609.6 -0.6677002562,52.0831479414,609.6 -0.6692511961,52.0798565142,609.6 -0.670244443,52.0764842696,609.6 -0.6706695909,52.0730669685,609.6 -0.6705222627,52.0696408411,609.6 -0.6698041505,52.0662422032,609.6 -0.6685229932,52.0629070708,609.6 -0.6666924882,52.0596707793,609.6 -0.6643321417,52.0565676093,609.6 -0.6614670575,52.0536304244,609.6 -0.6581276674,52.0508903241,609.6 -0.6543494062,52.0483763159,609.6 -0.6501723341,52.0461150089,609.6 -0.6456407123,52.044130334,609.6 -0.6408025339,52.0424432914,609.6 -0.6357090174,52.04107173,609.6 -0.6304140667,52.0400301594,609.6 -0.6249737029,52.0393295974,609.6 -0.6194454757,52.0389774541,609.6 -0.6138878577,52.0389774541,609.6 -0.6083596304,52.0393295974,609.6 -0.6029192666,52.0400301594,609.6 -0.5976243159,52.04107173,609.6 -0.5925307995,52.0424432914,609.6 -0.5876926211,52.044130334,609.6 -0.5831609992,52.0461150089,609.6 -0.5789839272,52.0483763159,609.6 -0.5752056659,52.0508903241,609.6 -0.5718662758,52.0536304244,609.6 -0.5690011916,52.0565676093,609.6 -0.5666408451,52.0596707793,609.6 -0.5648103401,52.0629070708,609.6 -0.5635291828,52.0662422032,609.6 -0.5628110707,52.0696408411,609.6 -0.5626637424,52.0730669685,609.6 -0.5630888903,52.0764842696,609.6 -0.5640821372,52.0798565142,609.6 -0.5656330771,52.0831479414,609.6 -0.5677253802,52.0863236401,609.6 -0.5703369616,52.089349919,609.6 -0.5734402114,52.0921946656,609.6 -0.5770022838,52.0948276879,609.6 -0.5809854437,52.0972210357,609.6 -0.5853474656,52.0993492989,609.6 -0.5900420809,52.1011898783,609.6 -0.59501947,52.1027232271,609.6 -0.6002267929,52.1039330593,609.6 -0.6056087522,52.1048065238,609.6 -0.6111081835,52.105334342,609.6 -0.6166666667,52.1055109067,609.6 + + + + + + EGRU218B CRANFIELD RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8034" txt_name="CRANFIELD RWY 03"><tr><td>520134N 0003915W -<br/>520151N 0004000W -<br/>520247N 0003903W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to<br/>520230N 0003819W -<br/>520134N 0003915W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6541416667,52.0262083333,609.6 -0.6385356667,52.0417852222,609.6 -0.6428961638,52.0431237873,609.6 -0.6470435365,52.0446991176,609.6 -0.6509440556,52.0464984167,609.6 -0.6665305556,52.0309361111,609.6 -0.6541416667,52.0262083333,609.6 + + + + + + EGRU218C CRANFIELD RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="8109" txt_name="CRANFIELD RWY 21"><tr><td>520710N 0003439W -<br/>520653N 0003355W -<br/>520552N 0003456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to<br/>520609N 0003541W -<br/>520710N 0003439W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5776055556,52.11955,609.6 -0.5946302778,52.1026172778,609.6 -0.5902709864,52.1012692712,609.6 -0.5861270565,52.0996846029,609.6 -0.5822322778,52.0978761944,609.6 -0.5651888889,52.1148222222,609.6 -0.5776055556,52.11955,609.6 + + + + + + EGRU219A BARKSTON HEATH + <table border="1" cellpadding="1" cellspacing="0" row_id="7889" txt_name="BARKSTON HEATH"><tr><td>A circle, 2 NM radius, centred at 525747N 0003337W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5603222222,52.996266979,609.6 -0.565994404,52.9960904368,609.6 -0.5716063218,52.9955626858,609.6 -0.577098356,52.994689333,609.6 -0.5824121696,52.9934796564,609.6 -0.5874913311,52.9919465064,609.6 -0.5922819171,52.9901061679,609.6 -0.5967330879,52.9879781863,609.6 -0.6007976284,52.9855851591,609.6 -0.6044324502,52.9829524945,609.6 -0.6075990482,52.9801081399,609.6 -0.6102639079,52.9770822846,609.6 -0.6123988586,52.9739070377,609.6 -0.6139813683,52.9706160864,609.6 -0.6149947786,52.9672443378,609.6 -0.6154284763,52.9638275476,609.6 -0.6152780005,52.9604019412,609.6 -0.6145450841,52.9570038284,609.6 -0.6132376293,52.9536692196,609.6 -0.6113696187,52.950433444,609.6 -0.6089609616,52.9473307757,609.6 -0.6060372784,52.9443940723,609.6 -0.6026296253,52.9416544268,609.6 -0.5987741625,52.9391408407,609.6 -0.5945117694,52.9368799173,609.6 -0.5898876105,52.9348955822,609.6 -0.5849506575,52.9332088307,609.6 -0.5797531725,52.9318375075,609.6 -0.5743501564,52.9307961187,609.6 -0.5687987704,52.9300956793,609.6 -0.5631577344,52.9297435978,609.6 -0.5574867101,52.9297435978,609.6 -0.551845674,52.9300956793,609.6 -0.546294288,52.9307961187,609.6 -0.540891272,52.9318375075,609.6 -0.5356937869,52.9332088307,609.6 -0.530756834,52.9348955822,609.6 -0.526132675,52.9368799173,609.6 -0.5218702819,52.9391408407,609.6 -0.5180148192,52.9416544268,609.6 -0.5146071661,52.9443940723,609.6 -0.5116834828,52.9473307757,609.6 -0.5092748257,52.950433444,609.6 -0.5074068151,52.9536692196,609.6 -0.5060993604,52.9570038284,609.6 -0.5053664439,52.9604019412,609.6 -0.5052159682,52.9638275476,609.6 -0.5056496659,52.9672443378,609.6 -0.5066630762,52.9706160864,609.6 -0.5082455858,52.9739070377,609.6 -0.5103805365,52.9770822846,609.6 -0.5130453963,52.9801081399,609.6 -0.5162119943,52.9829524945,609.6 -0.519846816,52.9855851591,609.6 -0.5239113565,52.9879781863,609.6 -0.5283625273,52.9901061679,609.6 -0.5331531134,52.9919465064,609.6 -0.5382322748,52.9934796564,609.6 -0.5435460884,52.994689333,609.6 -0.5490381227,52.9955626858,609.6 -0.5546500404,52.9960904368,609.6 -0.5603222222,52.996266979,609.6 + + + + + + EGRU219B BARKSTON HEATH RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7741" txt_name="BARKSTON HEATH RWY 06"><tr><td>525553N 0003743W -<br/>525620N 0003812W -<br/>525656N 0003637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525629N 0003608W -<br/>525553N 0003743W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6285518889,52.931293,609.6 -0.6023251944,52.9414361667,609.6 -0.6053708766,52.9438101274,609.6 -0.6080502032,52.9463402205,609.6 -0.6103413333,52.9490058611,609.6 -0.6365603611,52.9388649167,609.6 -0.6285518889,52.931293,609.6 + + + + + + EGRU219C BARKSTON HEATH RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7529" txt_name="BARKSTON HEATH RWY 24"><tr><td>525943N 0002924W -<br/>525916N 0002856W -<br/>525837N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525904N 0003106W -<br/>525943N 0002924W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4901250278,52.9953680278,609.6 -0.51829125,52.9845253889,609.6 -0.5152459863,52.9821499092,609.6 -0.5125682452,52.979618365,609.6 -0.5102798056,52.9769513889,609.6 -0.4821061111,52.9877961667,609.6 -0.4901250278,52.9953680278,609.6 + + + + + + EGRU219D BARKSTON HEATH RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7774" txt_name="BARKSTON HEATH RWY 10"><tr><td>525756N 0003847W -<br/>525827N 0003836W -<br/>525813N 0003651W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525741N 0003655W -<br/>525756N 0003847W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6465194444,52.9655111111,609.6 -0.6153789167,52.9613583333,609.6 -0.6153974861,52.964387462,609.6 -0.6149598521,52.9674050634,609.6 -0.6140695278,52.9703861389,609.6 -0.6432944444,52.9742833333,609.6 -0.6465194444,52.9655111111,609.6 + + + + + + EGRU219E BARKSTON HEATH RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7644" txt_name="BARKSTON HEATH RWY 28"><tr><td>525709N 0002854W -<br/>525638N 0002906W -<br/>525651N 0003042W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525721N 0003023W -<br/>525709N 0002854W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4816833333,52.9526333333,609.6 -0.5064422778,52.9559658056,609.6 -0.5077235244,52.9530372713,609.6 -0.509440117,52.9501911894,609.6 -0.51157775,52.9474511111,609.6 -0.4849027778,52.9438611111,609.6 -0.4816833333,52.9526333333,609.6 + + + + + + EGRU219F BARKSTON HEATH RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7738" txt_name="BARKSTON HEATH RWY 18"><tr><td>530037N 0003400W -<br/>530038N 0003306W -<br/>525945N 0003303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525946N 0003356W -<br/>530037N 0003400W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5665701111,53.0101906944,609.6 -0.5656517222,52.9961111667,609.6 -0.5606649345,52.9962663366,609.6 -0.5556753315,52.9961485956,609.6 -0.5507238889,52.9957589167,609.6 -0.5516831111,53.0105427222,609.6 -0.5665701111,53.0101906944,609.6 + + + + + + EGRU219G BARKSTON HEATH RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7607" txt_name="BARKSTON HEATH RWY 36"><tr><td>525449N 0003243W -<br/>525448N 0003337W -<br/>525547N 0003341W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to<br/>525551N 0003247W -<br/>525449N 0003243W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.54540575,52.9136083333,609.6 -0.5465145,52.9307613889,609.6 -0.5513929375,52.9301394272,609.6 -0.5563443631,52.9297863492,609.6 -0.5613283056,52.9297050556,609.6 -0.5602594722,52.9132563056,609.6 -0.54540575,52.9136083333,609.6 + + + + + + EGRU220A WITTERING + <table border="1" cellpadding="1" cellspacing="0" row_id="8107" txt_name="WITTERING"><tr><td>A circle, 2.5 NM radius, centred at 523647N 0002833W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4759055556,52.6546625512,609.6 -0.4822183994,52.6544848957,609.6 -0.4884772319,52.6539534489,609.6 -0.4946285077,52.6530727579,609.6 -0.5006196095,52.6518503568,609.6 -0.5063993013,52.6502967026,609.6 -0.5119181697,52.6484250848,609.6 -0.5171290496,52.6462515105,609.6 -0.5219874283,52.6437945672,609.6 -0.5264518282,52.6410752618,609.6 -0.5304841609,52.6381168408,609.6 -0.5340500523,52.6349445897,609.6 -0.5371191351,52.631585616,609.6 -0.5396653057,52.6280686166,609.6 -0.5416669443,52.6244236311,609.6 -0.5431070957,52.6206817852,609.6 -0.5439736099,52.6168750233,609.6 -0.5442592411,52.6130358359,609.6 -0.5439617044,52.6091969817,609.6 -0.54308369,52.6053912083,609.6 -0.5416328355,52.6016509723,609.6 -0.5396216554,52.5980081635,609.6 -0.5370674297,52.5944938332,609.6 -0.5339920525,52.5911379304,609.6 -0.5304218419,52.5879690473,609.6 -0.5263873122,52.5850141767,609.6 -0.5219229123,52.5822984832,609.6 -0.5170667305,52.5798450902,609.6 -0.5118601699,52.5776748839,609.6 -0.5063475957,52.575806337,609.6 -0.5005759591,52.574255352,609.6 -0.4945943989,52.5730351276,609.6 -0.4884538261,52.5721560465,609.6 -0.4822064938,52.5716255882,609.6 -0.4759055556,52.5714482659,609.6 -0.4696046173,52.5716255882,609.6 -0.463357285,52.5721560465,609.6 -0.4572167122,52.5730351276,609.6 -0.451235152,52.574255352,609.6 -0.4454635154,52.575806337,609.6 -0.4399509412,52.5776748839,609.6 -0.4347443806,52.5798450902,609.6 -0.4298881989,52.5822984832,609.6 -0.4254237989,52.5850141767,609.6 -0.4213892692,52.5879690473,609.6 -0.4178190586,52.5911379304,609.6 -0.4147436814,52.5944938332,609.6 -0.4121894557,52.5980081635,609.6 -0.4101782756,52.6016509723,609.6 -0.4087274211,52.6053912083,609.6 -0.4078494068,52.6091969817,609.6 -0.40755187,52.6130358359,609.6 -0.4078375012,52.6168750233,609.6 -0.4087040154,52.6206817852,609.6 -0.4101441668,52.6244236311,609.6 -0.4121458054,52.6280686166,609.6 -0.414691976,52.631585616,609.6 -0.4177610588,52.6349445897,609.6 -0.4213269502,52.6381168408,609.6 -0.4253592829,52.6410752618,609.6 -0.4298236828,52.6437945672,609.6 -0.4346820616,52.6462515105,609.6 -0.4398929414,52.6484250848,609.6 -0.4454118098,52.6502967026,609.6 -0.4511915016,52.6518503568,609.6 -0.4571826034,52.6530727579,609.6 -0.4633338792,52.6539534489,609.6 -0.4695927117,52.6544848957,609.6 -0.4759055556,52.6546625512,609.6 + + + + + + EGRU220B WITTERING RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="8000" txt_name="WITTERING RWY 07"><tr><td>523532N 0003349W -<br/>523603N 0003404W -<br/>523619N 0003235W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to<br/>523548N 0003220W -<br/>523532N 0003349W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5636166667,52.5921861111,609.6 -0.5387953333,52.5967718611,609.6 -0.5405613037,52.5995733524,609.6 -0.5419912752,52.6024450404,609.6 -0.54307775,52.605372,609.6 -0.5678833333,52.6007888889,609.6 -0.5636166667,52.5921861111,609.6 + + + + + + EGRU220C WITTERING RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7714" txt_name="WITTERING RWY 25"><tr><td>523802N 0002317W -<br/>523731N 0002302W -<br/>523715N 0002431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to<br/>523746N 0002447W -<br/>523802N 0002317W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3881305556,52.6338611111,609.6 -0.4129719444,52.6293098333,609.6 -0.4112122551,52.6265062386,609.6 -0.409789456,52.6236327327,609.6 -0.4087108889,52.6207042778,609.6 -0.3838527778,52.6252583333,609.6 -0.3881305556,52.6338611111,609.6 + + + + + + EGRU222A OLD WARDEN + <table border="1" cellpadding="1" cellspacing="0" row_id="7567" txt_name="OLD WARDEN"><tr><td>A circle, 2 NM radius, centred at 520512N 0001907W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3186111111,52.1199552691,609.6 -0.3241713908,52.1197787048,609.6 -0.3296725996,52.1192508877,609.6 -0.3350562982,52.118377425,609.6 -0.3402653038,52.1171675954,609.6 -0.3452443011,52.1156342498,609.6 -0.3499404329,52.1137936743,609.6 -0.3543038634,52.1116654157,609.6 -0.3582883093,52.1092720731,609.6 -0.3618515313,52.1066390567,609.6 -0.364955782,52.1037943165,609.6 -0.3675682054,52.1007680445,609.6 -0.3696611824,52.0975923532,609.6 -0.3712126211,52.0943009337,609.6 -0.3722061867,52.0909286972,609.6 -0.3726314698,52.0875114044,609.6 -0.3724840918,52.0840852855,609.6 -0.3717657458,52.0806866562,609.6 -0.3704841729,52.0773515323,609.6 -0.3686530753,52.0741152492,609.6 -0.3662919654,52.0710120873,609.6 -0.3634259553,52.0680749102,609.6 -0.3600854865,52.0653348174,609.6 -0.3563060054,52.062820816,609.6 -0.3521275851,52.0605595152,609.6 -0.347594501,52.0585748458,609.6 -0.3427547618,52.056887808,609.6 -0.3376596025,52.0555162505,609.6 -0.3323629441,52.0544746828,609.6 -0.326920826,52.0537741228,609.6 -0.3213908161,52.0534219804,609.6 -0.3158314061,52.0534219804,609.6 -0.3103013962,52.0537741228,609.6 -0.3048592781,52.0544746828,609.6 -0.2995626198,52.0555162505,609.6 -0.2944674604,52.056887808,609.6 -0.2896277212,52.0585748458,609.6 -0.2850946371,52.0605595152,609.6 -0.2809162168,52.062820816,609.6 -0.2771367357,52.0653348174,609.6 -0.273796267,52.0680749102,609.6 -0.2709302568,52.0710120873,609.6 -0.2685691469,52.0741152492,609.6 -0.2667380493,52.0773515323,609.6 -0.2654564765,52.0806866562,609.6 -0.2647381305,52.0840852855,609.6 -0.2645907525,52.0875114044,609.6 -0.2650160355,52.0909286972,609.6 -0.2660096011,52.0943009337,609.6 -0.2675610398,52.0975923532,609.6 -0.2696540168,52.1007680445,609.6 -0.2722664402,52.1037943165,609.6 -0.2753706909,52.1066390567,609.6 -0.2789339129,52.1092720731,609.6 -0.2829183588,52.1116654157,609.6 -0.2872817893,52.1137936743,609.6 -0.2919779211,52.1156342498,609.6 -0.2969569184,52.1171675954,609.6 -0.302165924,52.118377425,609.6 -0.3075496226,52.1192508877,609.6 -0.3130508314,52.1197787048,609.6 -0.3186111111,52.1199552691,609.6 + + + + + + EGRU222B OLD WARDEN RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7555" txt_name="OLD WARDEN RWY 03"><tr><td>520232N 0002041W -<br/>520245N 0002128W -<br/>520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to<br/>520318N 0002006W -<br/>520232N 0002041W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3446666667,52.0421166667,609.6 -0.3348690556,52.0549213889,609.6 -0.3394451207,52.0559533739,609.6 -0.3438518961,52.057235281,609.6 -0.3480535556,52.0587566944,609.6 -0.3578472222,52.0459527778,609.6 -0.3446666667,52.0421166667,609.6 + + + + + + EGRU222C OLD WARDEN RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7707" txt_name="OLD WARDEN RWY 21"><tr><td>520753N 0001732W -<br/>520739N 0001645W -<br/>520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to<br/>520706N 0001808W -<br/>520753N 0001732W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2923277778,52.1314555556,609.6 -0.3023411667,52.1184116944,609.6 -0.2977597768,52.11737904,609.6 -0.2933484744,52.1160962173,609.6 -0.2891432222,52.1145736944,609.6 -0.279125,52.1276194444,609.6 -0.2923277778,52.1314555556,609.6 + + + + + + EGRU222D OLD WARDEN RWY 03X + <table border="1" cellpadding="1" cellspacing="0" row_id="7995" txt_name="OLD WARDEN RWY 03X"><tr><td>520218N 0002051W -<br/>520231N 0002139W -<br/>520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to<br/>520318N 0002005W -<br/>520218N 0002051W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3476277778,52.0382166667,609.6 -0.3348561389,52.0549188611,609.6 -0.339432504,52.0559501295,609.6 -0.3438396998,52.0572313152,609.6 -0.3480418889,52.0587520278,609.6 -0.3608055556,52.0420527778,609.6 -0.3476277778,52.0382166667,609.6 + + + + + + EGRU222E OLD WARDEN RWY 21X + <table border="1" cellpadding="1" cellspacing="0" row_id="7785" txt_name="OLD WARDEN RWY 21X"><tr><td>520753N 0001732W -<br/>520739N 0001645W -<br/>520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to<br/>520706N 0001808W -<br/>520753N 0001732W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2923444444,52.1314611111,609.6 -0.3023537222,52.1184141389,609.6 -0.2977706736,52.1173818267,609.6 -0.2933577082,52.1160992039,609.6 -0.2891508333,52.1145767222,609.6 -0.2791361111,52.127625,609.6 -0.2923444444,52.1314611111,609.6 + + + + + + EGRU223A PETERBOROUGH/CONINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="8101" txt_name="PETERBOROUGH/CONINGTON"><tr><td>A circle, 2 NM radius, centred at 522805N 0001503W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2509305556,52.5013558845,609.6 -0.2565388288,52.5011793299,609.6 -0.2620875194,52.5006515417,609.6 -0.2675176819,52.499778127,609.6 -0.2727716385,52.4985683643,609.6 -0.2777935952,52.4970351043,609.6 -0.2825302375,52.4951946324,609.6 -0.286931299,52.4930664948,609.6 -0.2909500969,52.4906732901,609.6 -0.2945440276,52.4880404274,609.6 -0.2976750187,52.4851958556,609.6 -0.3003099319,52.4821697656,609.6 -0.3024209115,52.4789942684,609.6 -0.3039856767,52.4757030532,609.6 -0.3049877539,52.4723310297,609.6 -0.3054166464,52.4689139562,609.6 -0.3052679403,52.4654880608,609.6 -0.3045433456,52.4620896568,609.6 -0.3032506726,52.4587547575,609.6 -0.3014037436,52.4555186956,609.6 -0.2990222414,52.4524157489,609.6 -0.2961314959,52.4494787782,609.6 -0.2927622124,52.4467388803,609.6 -0.2889501434,52.4442250598,609.6 -0.2847357077,52.4419639235,609.6 -0.2801635622,52.4399793997,609.6 -0.2752821285,52.4382924865,609.6 -0.2701430821,52.4369210311,609.6 -0.2648008074,52.4358795413,609.6 -0.2593118247,52.4351790338,609.6 -0.2537341961,52.434826918,609.6 -0.248126915,52.434826918,609.6 -0.2425492865,52.4351790338,609.6 -0.2370603038,52.4358795413,609.6 -0.231718029,52.4369210311,609.6 -0.2265789826,52.4382924865,609.6 -0.221697549,52.4399793997,609.6 -0.2171254034,52.4419639235,609.6 -0.2129109677,52.4442250598,609.6 -0.2090988987,52.4467388803,609.6 -0.2057296152,52.4494787782,609.6 -0.2028388697,52.4524157489,609.6 -0.2004573675,52.4555186956,609.6 -0.1986104385,52.4587547575,609.6 -0.1973177656,52.4620896568,609.6 -0.1965931708,52.4654880608,609.6 -0.1964444647,52.4689139562,609.6 -0.1968733572,52.4723310297,609.6 -0.1978754344,52.4757030532,609.6 -0.1994401997,52.4789942684,609.6 -0.2015511792,52.4821697656,609.6 -0.2041860924,52.4851958556,609.6 -0.2073170836,52.4880404274,609.6 -0.2109110142,52.4906732901,609.6 -0.2149298121,52.4930664948,609.6 -0.2193308736,52.4951946324,609.6 -0.2240675159,52.4970351043,609.6 -0.2290894726,52.4985683643,609.6 -0.2343434292,52.499778127,609.6 -0.2397735918,52.5006515417,609.6 -0.2453222823,52.5011793299,609.6 -0.2509305556,52.5013558845,609.6 + + + + + + EGRU223B PETERBOROUGH/CONINGTON RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7584" txt_name="PETERBOROUGH/CONINGTON RWY 10"><tr><td>522803N 0001956W -<br/>522835N 0001952W -<br/>522830N 0001815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to<br/>522758N 0001819W -<br/>522803N 0001956W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3321527778,52.4673944444,609.6 -0.3053404444,52.4661358889,609.6 -0.3054061395,52.4691397138,609.6 -0.3050281085,52.4721349212,609.6 -0.3042093333,52.4750971111,609.6 -0.3310083333,52.4763555556,609.6 -0.3321527778,52.4673944444,609.6 + + + + + + EGRU223C PETERBOROUGH/CONINGTON RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7867" txt_name="PETERBOROUGH/CONINGTON RWY 28"><tr><td>522808N 0001017W -<br/>522735N 0001021W -<br/>522740N 0001152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to<br/>522812N 0001147W -<br/>522808N 0001017W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1714472222,52.4687722222,609.6 -0.1965159444,52.4699780556,609.6 -0.1964576045,52.4669748648,609.6 -0.1968427065,52.4639806853,609.6 -0.1976680278,52.4610198889,609.6 -0.1725861111,52.4598138889,609.6 -0.1714472222,52.4687722222,609.6 + + + + + + EGRU224A FENLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="7782" txt_name="FENLAND"><tr><td>A circle, 2 NM radius, centred at 524422N 0000148W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0298666667,52.7727293506,609.6 -0.0355097506,52.7725528028,609.6 -0.0410928807,52.7720250351,609.6 -0.0465567445,52.7711516544,609.6 -0.051843305,52.769941939,609.6 -0.0568964209,52.7684087394,609.6 -0.0616624461,52.7665683408,609.6 -0.0660908021,52.7644402889,609.6 -0.0701345158,52.7620471818,609.6 -0.0737507198,52.7594144279,609.6 -0.076901106,52.7565699754,609.6 -0.0795523311,52.7535440143,609.6 -0.0816763678,52.7503686545,609.6 -0.0832507985,52.7470775843,609.6 -0.084259049,52.7437057116,609.6 -0.084690559,52.7402887937,609.6 -0.0845408891,52.7368630569,609.6 -0.0838117617,52.7334648127,609.6 -0.0825110373,52.7301300729,609.6 -0.0806526253,52.726894168,609.6 -0.078256332,52.7237913741,609.6 -0.0753476454,52.7208545501,609.6 -0.0719574621,52.7181147907,609.6 -0.0681217567,52.7156010987,609.6 -0.0638811987,52.7133400792,609.6 -0.0592807215,52.7113556589,609.6 -0.0543690465,52.7096688344,609.6 -0.0491981686,52.7082974515,609.6 -0.0438228081,52.7072560171,609.6 -0.0382998343,52.706555547,609.6 -0.0326876677,52.70620345,609.6 -0.0270456657,52.70620345,609.6 -0.021433499,52.706555547,609.6 -0.0159105253,52.7072560171,609.6 -0.0105351647,52.7082974515,609.6 -0.0053642868,52.7096688344,609.6 -4.526119E-4,52.7113556589,609.6 0.0041478653,52.7133400792,609.6 0.0083884233,52.7156010987,609.6 0.0122241288,52.7181147907,609.6 0.0156143121,52.7208545501,609.6 0.0185229986,52.7237913741,609.6 0.020919292,52.726894168,609.6 0.0227777039,52.7301300729,609.6 0.0240784284,52.7334648127,609.6 0.0248075558,52.7368630569,609.6 0.0249572257,52.7402887937,609.6 0.0245257156,52.7437057116,609.6 0.0235174651,52.7470775843,609.6 0.0219430344,52.7503686545,609.6 0.0198189978,52.7535440143,609.6 0.0171677727,52.7565699754,609.6 0.0140173865,52.7594144279,609.6 0.0104011825,52.7620471818,609.6 0.0063574687,52.7644402889,609.6 0.0019291128,52.7665683408,609.6 -0.0028369125,52.7684087394,609.6 -0.0078900283,52.769941939,609.6 -0.0131765888,52.7711516544,609.6 -0.0186404526,52.7720250351,609.6 -0.0242235827,52.7725528028,609.6 -0.0298666667,52.7727293506,609.6 + + + + + + EGRU224B FENLAND RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7814" txt_name="FENLAND RWY 18"><tr><td>524711N 0000210W -<br/>524710N 0000116W -<br/>524620N 0000118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to<br/>524621N 0000211W -<br/>524711N 0000210W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.03605,52.7863611111,609.6 -0.0364105278,52.7724917222,609.6 -0.0314710385,52.7727151248,609.6 -0.0265184494,52.7726673154,609.6 -0.0215931944,52.7723486944,609.6 -0.0212277778,52.7862166667,609.6 -0.03605,52.7863611111,609.6 + + + + + + EGRU224C FENLAND RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7899" txt_name="FENLAND RWY 36"><tr><td>524130N 0000125W -<br/>524131N 0000219W -<br/>524224N 0000217W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to<br/>524223N 0000124W -<br/>524130N 0000125W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0237138889,52.6916888889,609.6 -0.0233277778,52.7063969722,609.6 -0.0282594659,52.7061736718,609.6 -0.0332042095,52.7062211083,609.6 -0.0381218333,52.7065389167,609.6 -0.0385027778,52.6918305556,609.6 -0.0237138889,52.6916888889,609.6 + + + + + + EGRU225A DUXFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="8153" txt_name="DUXFORD"><tr><td>A circle, 2 NM radius, centred at 520526N 0000753E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1315027778,52.123808025,609.6 0.1259420186,52.1236314608,609.6 0.1204403355,52.123103644,609.6 0.1150561727,52.1222301818,609.6 0.109846718,52.1210203528,609.6 0.1048672915,52.1194870082,609.6 0.1001707551,52.1176464337,609.6 0.0958069486,52.1155181763,609.6 0.0918221595,52.1131248351,609.6 0.0882586307,52.1104918203,609.6 0.0851541128,52.1076470817,609.6 0.0825414648,52.1046208116,609.6 0.0804483079,52.1014451223,609.6 0.0788967361,52.0981537048,609.6 0.0779030855,52.0947814705,609.6 0.0774777663,52.0913641799,609.6 0.0776251576,52.0879380633,609.6 0.078343566,52.0845394362,609.6 0.0796252498,52.0812043146,609.6 0.0814565055,52.0779680338,609.6 0.0838178192,52.0748648741,609.6 0.0866840764,52.0719276991,609.6 0.090024833,52.0691876082,609.6 0.0938046397,52.0666736086,609.6 0.0979834198,52.0644123095,609.6 0.1025168941,52.0624276416,609.6 0.1073570499,52.060740605,609.6 0.1124526477,52.0593690485,609.6 0.1177497618,52.0583274817,609.6 0.1231923481,52.0576269221,609.6 0.1287228336,52.0572747801,609.6 0.1342827219,52.0572747801,609.6 0.1398132075,52.0576269221,609.6 0.1452557938,52.0583274817,609.6 0.1505529079,52.0593690485,609.6 0.1556485057,52.060740605,609.6 0.1604886614,52.0624276416,609.6 0.1650221357,52.0644123095,609.6 0.1692009158,52.0666736086,609.6 0.1729807226,52.0691876082,609.6 0.1763214791,52.0719276991,609.6 0.1791877364,52.0748648741,609.6 0.18154905,52.0779680338,609.6 0.1833803058,52.0812043146,609.6 0.1846619895,52.0845394362,609.6 0.1853803979,52.0879380633,609.6 0.1855277892,52.0913641799,609.6 0.1851024701,52.0947814705,609.6 0.1841088195,52.0981537048,609.6 0.1825572476,52.1014451223,609.6 0.1804640907,52.1046208116,609.6 0.1778514427,52.1076470817,609.6 0.1747469248,52.1104918203,609.6 0.1711833961,52.1131248351,609.6 0.167198607,52.1155181763,609.6 0.1628348005,52.1176464337,609.6 0.158138264,52.1194870082,609.6 0.1531588375,52.1210203528,609.6 0.1479493829,52.1222301818,609.6 0.1425652201,52.123103644,609.6 0.137063537,52.1236314608,609.6 0.1315027778,52.123808025,609.6 + + + + + + EGRU225B DUXFORD RWY 06L + <table border="1" cellpadding="1" cellspacing="0" row_id="7639" txt_name="DUXFORD RWY 06L"><tr><td>520342N 0000358E -<br/>520409N 0000331E -<br/>520441N 0000453E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to<br/>520413N 0000519E -<br/>520342N 0000358E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0662027778,52.0616638889,609.6 0.0885908611,52.0702925556,609.6 0.0858030761,52.0727600356,609.6 0.0833876371,52.075372398,609.6 0.0813643056,52.0781083611,609.6 0.0584833333,52.0692888889,609.6 0.0662027778,52.0616638889,609.6 + + + + + + EGRU225C DUXFORD RWY 24R + <table border="1" cellpadding="1" cellspacing="0" row_id="8170" txt_name="DUXFORD RWY 24R"><tr><td>520716N 0001135E -<br/>520648N 0001203E -<br/>520619N 0001047E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to<br/>520646N 0001018E -<br/>520716N 0001135E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1931527778,52.1210833333,609.6 0.1716298056,52.1128239167,609.6 0.1747339861,52.1105024373,609.6 0.177484965,52.1080179068,609.6 0.1798603056,52.1053906111,609.6 0.2008861111,52.1134583333,609.6 0.1931527778,52.1210833333,609.6 + + + + + + EGRU225D DUXFORD RWY 06R + <table border="1" cellpadding="1" cellspacing="0" row_id="7773" txt_name="DUXFORD RWY 06R"><tr><td>520334N 0000352E -<br/>520401N 0000325E -<br/>520437N 0000456E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to<br/>520409N 0000524E -<br/>520334N 0000352E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.06455875,52.0594518333,609.6 0.0899554167,52.0692389444,609.6 0.0870104264,52.0716326258,609.6 0.0844272855,52.0741801083,609.6 0.0822270556,52.0768606667,609.6 0.0568375833,52.0670756667,609.6 0.06455875,52.0594518333,609.6 + + + + + + EGRU225E DUXFORD RWY 24L + <table border="1" cellpadding="1" cellspacing="0" row_id="7833" txt_name="DUXFORD RWY 24L"><tr><td>520716N 0001150E -<br/>520648N 0001218E -<br/>520615N 0001051E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to<br/>520642N 0001023E -<br/>520716N 0001150E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1973161944,52.1210931389,609.6 0.1730776667,52.1117941389,609.6 0.1760220254,52.1093989495,609.6 0.1786034196,52.1068500334,609.6 0.1808008611,52.1041681667,609.6 0.2050466944,52.1134693889,609.6 0.1973161944,52.1210931389,609.6 + + + + + + EGRU226A CAMBRIDGE + <table border="1" cellpadding="1" cellspacing="0" row_id="7805" txt_name="CAMBRIDGE"><tr><td>A circle, 2.5 NM radius, centred at 521218N 0001030E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.175,52.2466098839,609.6 0.1687452292,52.2464322185,609.6 0.1625439707,52.2459007422,609.6 0.1564492751,52.2450200018,609.6 0.1505132739,52.2437975319,609.6 0.1447867299,52.2422437896,609.6 0.1393186007,52.2403720645,609.6 0.1341556167,52.2381983642,609.6 0.1293418805,52.2357412764,609.6 0.1249184884,52.2330218089,609.6 0.1209231787,52.2300632087,609.6 0.1173900105,52.2268907621,609.6 0.1143490731,52.2235315779,609.6 0.111826232,52.2200143539,609.6 0.1098429104,52.2163691314,609.6 0.10841591,52.2126270374,609.6 0.1075572719,52.2088200185,609.6 0.1072741782,52.2049805669,609.6 0.1075688958,52.2011414438,609.6 0.108438762,52.1973353987,609.6 0.1098762123,52.1935948911,609.6 0.1118688498,52.1899518133,609.6 0.1143995555,52.1864372194,609.6 0.1174466383,52.1830810609,609.6 0.1209840236,52.179911933,609.6 0.1249814783,52.176956831,609.6 0.1294048705,52.1742409224,609.6 0.1342164617,52.1717873329,609.6 0.1393752286,52.1696169512,609.6 0.1448372124,52.1677482519,609.6 0.1505558918,52.1661971396,609.6 0.1564825772,52.1649768144,609.6 0.1625668229,52.1640976604,609.6 0.1687568532,52.163567158,609.6 0.175,52.163389821,609.6 0.1812431468,52.163567158,609.6 0.1874331771,52.1640976604,609.6 0.1935174228,52.1649768144,609.6 0.1994441082,52.1661971396,609.6 0.2051627876,52.1677482519,609.6 0.2106247714,52.1696169512,609.6 0.2157835383,52.1717873329,609.6 0.2205951295,52.1742409224,609.6 0.2250185217,52.176956831,609.6 0.2290159764,52.179911933,609.6 0.2325533617,52.1830810609,609.6 0.2356004445,52.1864372194,609.6 0.2381311502,52.1899518133,609.6 0.2401237877,52.1935948911,609.6 0.241561238,52.1973353987,609.6 0.2424311042,52.2011414438,609.6 0.2427258218,52.2049805669,609.6 0.2424427281,52.2088200185,609.6 0.24158409,52.2126270374,609.6 0.2401570896,52.2163691314,609.6 0.238173768,52.2200143539,609.6 0.2356509269,52.2235315779,609.6 0.2326099895,52.2268907621,609.6 0.2290768213,52.2300632087,609.6 0.2250815116,52.2330218089,609.6 0.2206581195,52.2357412764,609.6 0.2158443833,52.2381983642,609.6 0.2106813993,52.2403720645,609.6 0.2052132701,52.2422437896,609.6 0.1994867261,52.2437975319,609.6 0.1935507249,52.2450200018,609.6 0.1874560293,52.2459007422,609.6 0.1812547708,52.2464322185,609.6 0.175,52.2466098839,609.6 + + + + + + EGRU226B CAMBRIDGE RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7605" txt_name="CAMBRIDGE RWY 05"><tr><td>521006N 0000655E -<br/>521030N 0000621E -<br/>521055N 0000708E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to<br/>521030N 0000742E -<br/>521006N 0000655E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1152138889,52.1682055556,609.6 0.1281993889,52.1749323889,609.6 0.1247950609,52.1770828876,609.6 0.1216513551,52.1793785446,609.6 0.1187846389,52.1818074444,609.6 0.1058055556,52.1750833333,609.6 0.1152138889,52.1682055556,609.6 + + + + + + EGRU226C CAMBRIDGE RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7895" txt_name="CAMBRIDGE RWY 23"><tr><td>521432N 0001409E -<br/>521407N 0001442E -<br/>521341N 0001352E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to<br/>521406N 0001319E -<br/>521432N 0001409E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.2357,52.2422222222,609.6 0.2218291389,52.23506925,609.6 0.2252353881,52.2329176763,609.6 0.2283799158,52.2306208904,609.6 0.2312463889,52.2281908611,609.6 0.245125,52.2353472222,609.6 0.2357,52.2422222222,609.6 + + + + + + EGRU226D CAMBRIDGE RWY 05G + <table border="1" cellpadding="1" cellspacing="0" row_id="7921" txt_name="CAMBRIDGE RWY 05G"><tr><td>521015N 0000728E -<br/>521039N 0000654E -<br/>521049N 0000713E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to<br/>521026N 0000749E -<br/>521015N 0000728E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.1243861111,52.1707,609.6 0.13028475,52.1737569444,609.6 0.1267348617,52.1758197269,609.6 0.1234358833,52.1780344549,609.6 0.120405,52.1803896111,609.6 0.114975,52.177575,609.6 0.1243861111,52.1707,609.6 + + + + + + EGRU226E CAMBRIDGE RWY 23G + <table border="1" cellpadding="1" cellspacing="0" row_id="7755" txt_name="CAMBRIDGE RWY 23G"><tr><td>521426N 0001413E -<br/>521402N 0001447E -<br/>521336N 0001358E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to<br/>521402N 0001326E -<br/>521426N 0001413E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.2369527778,52.2406555556,609.6 0.2237949167,52.2338656944,609.6 0.2270582421,52.2316275242,609.6 0.2300497493,52.2292505454,609.6 0.2327538611,52.2267471667,609.6 0.2463805556,52.2337777778,609.6 0.2369527778,52.2406555556,609.6 + + + + + + EGRU227A MILDENHALL + <table border="1" cellpadding="1" cellspacing="0" row_id="8043" txt_name="MILDENHALL"><tr><td>A circle, 2.5 NM radius, centred at 522143N 0002911E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4864055556,52.4035421051,609.6 0.4801286155,52.4033644435,609.6 0.4739053782,52.4028329786,609.6 0.4677890832,52.4019522573,609.6 0.4618320474,52.4007298139,609.6 0.4560852143,52.3991761056,609.6 0.4505977154,52.3973044218,609.6 0.4454164473,52.3951307702,609.6 0.4405856688,52.3926737381,609.6 0.4361466219,52.389954333,609.6 0.4321371786,52.3869958019,609.6 0.4285915182,52.3838234307,609.6 0.4255398363,52.3804643276,609.6 0.423008089,52.3769471901,609.6 0.4210177748,52.3733020589,609.6 0.4195857539,52.3695600605,609.6 0.4187241089,52.3657531405,609.6 0.4184400464,52.3619137907,609.6 0.4187358401,52.3580747711,609.6 0.4196088168,52.3542688306,609.6 0.421051384,52.3505284275,609.6 0.4230511001,52.3468854532,609.6 0.4255907844,52.3433709608,609.6 0.4286486685,52.3400149007,609.6 0.4321985849,52.336845867,609.6 0.436210193,52.333890854,609.6 0.4406492399,52.3311750281,609.6 0.4454778536,52.3287215143,609.6 0.4506548658,52.3265512,609.6 0.4561361626,52.3246825593,609.6 0.4618750585,52.323131496,609.6 0.4678226925,52.3219112096,609.6 0.4739284412,52.3210320836,609.6 0.4801403467,52.3205015982,609.6 0.4864055556,52.3203242668,609.6 0.4926707644,52.3205015982,609.6 0.4988826699,52.3210320836,609.6 0.5049884186,52.3219112096,609.6 0.5109360526,52.323131496,609.6 0.5166749486,52.3246825593,609.6 0.5221562453,52.3265512,609.6 0.5273332576,52.3287215143,609.6 0.5321618712,52.3311750281,609.6 0.5366009181,52.333890854,609.6 0.5406125262,52.336845867,609.6 0.5441624426,52.3400149007,609.6 0.5472203267,52.3433709608,609.6 0.5497600111,52.3468854532,609.6 0.5517597271,52.3505284275,609.6 0.5532022944,52.3542688306,609.6 0.554075271,52.3580747711,609.6 0.5543710647,52.3619137907,609.6 0.5540870022,52.3657531405,609.6 0.5532253572,52.3695600605,609.6 0.5517933363,52.3733020589,609.6 0.5498030221,52.3769471901,609.6 0.5472712748,52.3804643276,609.6 0.5442195929,52.3838234307,609.6 0.5406739325,52.3869958019,609.6 0.5366644892,52.389954333,609.6 0.5322254424,52.3926737381,609.6 0.5273946639,52.3951307702,609.6 0.5222133957,52.3973044218,609.6 0.5167258968,52.3991761056,609.6 0.5109790637,52.4007298139,609.6 0.5050220279,52.4019522573,609.6 0.4989057329,52.4028329786,609.6 0.4926824956,52.4033644435,609.6 0.4864055556,52.4035421051,609.6 + + + + + + EGRU227B MILDENHALL RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7835" txt_name="MILDENHALL RWY 11"><tr><td>522215N 0002335E -<br/>522246N 0002348E -<br/>522233N 0002520E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to<br/>522201N 0002508E -<br/>522215N 0002335E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.39318525,52.3707543333,609.6 0.41895225,52.3670513611,609.6 0.4197280497,52.3700143536,609.6 0.420850861,52.3729354022,609.6 0.4223148889,52.3757993056,609.6 0.39655725,52.3795009722,609.6 0.39318525,52.3707543333,609.6 + + + + + + EGRU227C MILDENHALL RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7987" txt_name="MILDENHALL RWY 29"><tr><td>522111N 0003446E -<br/>522040N 0003434E -<br/>522053N 0003302E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to<br/>522124N 0003314E -<br/>522111N 0003446E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5795797222,52.3530635,609.6 0.5538478611,52.3567994722,609.6 0.5530659598,52.3538371034,609.6 0.5519375386,52.3509169327,609.6 0.5504685278,52.3480541389,609.6 0.5762097222,52.3443168611,609.6 0.5795797222,52.3530635,609.6 + + + + + + EGRU228A MARHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7800" txt_name="MARHAM"><tr><td>A circle, 2.5 NM radius, centred at 523854N 0003302E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5505555556,52.6899400798,609.6 0.5442376252,52.6897624251,609.6 0.5379737499,52.6892309809,609.6 0.5318175182,52.6883502941,609.6 0.5258215902,52.6871278989,609.6 0.5200372433,52.6855742523,609.6 0.5145139307,52.6837026437,609.6 0.5092988557,52.6815290804,609.6 0.5044365668,52.6790721494,609.6 0.4999685751,52.676352858,609.6 0.4959329997,52.6733944524,609.6 0.4923642421,52.6702222182,609.6 0.4892926942,52.6668632627,609.6 0.4867444802,52.6633462825,609.6 0.4847412373,52.6597013175,609.6 0.4832999341,52.655959493,609.6 0.4824327301,52.6521527532,609.6 0.4821468767,52.6483135886,609.6 0.4824446604,52.6444747577,609.6 0.4833233885,52.6406690077,609.6 0.4847754171,52.6369287951,609.6 0.4867882214,52.6332860095,609.6 0.4893445072,52.629771702,609.6 0.4924223626,52.6264158213,609.6 0.4959954484,52.6232469594,609.6 0.5000332254,52.6202921087,609.6 0.5045012171,52.6175764338,609.6 0.5093613045,52.6151230578,609.6 0.5145720512,52.6129528667,609.6 0.5200890564,52.6110843329,609.6 0.5258653315,52.609533359,609.6 0.531851698,52.6083131433,609.6 0.5379972043,52.6074340684,609.6 0.5442495556,52.606903614,609.6 0.5505555556,52.606726293,609.6 0.5568615556,52.606903614,609.6 0.5631139068,52.6074340684,609.6 0.5692594131,52.6083131433,609.6 0.5752457796,52.609533359,609.6 0.5810220547,52.6110843329,609.6 0.5865390599,52.6129528667,609.6 0.5917498066,52.6151230578,609.6 0.596609894,52.6175764338,609.6 0.6010778857,52.6202921087,609.6 0.6051156627,52.6232469594,609.6 0.6086887485,52.6264158213,609.6 0.6117666039,52.629771702,609.6 0.6143228897,52.6332860095,609.6 0.616335694,52.6369287951,609.6 0.6177877226,52.6406690077,609.6 0.6186664507,52.6444747577,609.6 0.6189642344,52.6483135886,609.6 0.618678381,52.6521527532,609.6 0.617811177,52.655959493,609.6 0.6163698738,52.6597013175,609.6 0.6143666309,52.6633462825,609.6 0.611818417,52.6668632627,609.6 0.608746869,52.6702222182,609.6 0.6051781114,52.6733944524,609.6 0.601142536,52.676352858,609.6 0.5966745443,52.6790721494,609.6 0.5918122554,52.6815290804,609.6 0.5865971804,52.6837026437,609.6 0.5810738678,52.6855742523,609.6 0.5752895209,52.6871278989,609.6 0.5692935929,52.6883502941,609.6 0.5631373613,52.6892309809,609.6 0.5568734859,52.6897624251,609.6 0.5505555556,52.6899400798,609.6 + + + + + + EGRU228B MARHAM RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="7700" txt_name="MARHAM RWY 01"><tr><td>523538N 0003307E -<br/>523543N 0003215E -<br/>523626N 0003225E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to<br/>523625N 0003319E -<br/>523538N 0003307E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5520111111,52.5939194444,609.6 0.5552008333,52.6068224167,609.6 0.5502455031,52.6067267341,609.6 0.5452918019,52.6068497766,609.6 0.5403657222,52.6071909167,609.6 0.5374194444,52.5952555556,609.6 0.5520111111,52.5939194444,609.6 + + + + + + EGRU228C MARHAM RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="8001" txt_name="MARHAM RWY 19"><tr><td>524200N 0003348E -<br/>524156N 0003441E -<br/>524114N 0003430E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to<br/>524122N 0003339E -<br/>524200N 0003348E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5633555556,52.7000972222,609.6 0.5607228889,52.6894784167,609.6 0.5656053044,52.6889216802,609.6 0.5704082912,52.6881511361,609.6 0.5751065,52.6871708333,609.6 0.5779833333,52.6987583333,609.6 0.5633555556,52.7000972222,609.6 + + + + + + EGRU228D MARHAM RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7582" txt_name="MARHAM RWY 06"><tr><td>523643N 0002837E -<br/>523710N 0002807E -<br/>523743N 0002925E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to<br/>523716N 0002956E -<br/>523643N 0002837E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.476925,52.6119888889,609.6 0.4987624167,52.6211635,609.6 0.4956781358,52.6235043234,609.6 0.4928787707,52.6259742675,609.6 0.4903788889,52.6285605,609.6 0.46855,52.6193888889,609.6 0.476925,52.6119888889,609.6 + + + + + + EGRU228E MARHAM RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7613" txt_name="MARHAM RWY 24"><tr><td>524104N 0003727E -<br/>524038N 0003757E -<br/>524005N 0003639E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to<br/>524032N 0003609E -<br/>524104N 0003727E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6240777778,52.6845638889,609.6 0.6023875,52.6754983333,609.6 0.6054717452,52.6731559687,609.6 0.6082699432,52.6706845186,609.6 0.6107675833,52.6680968611,609.6 0.6324694444,52.6771666667,609.6 0.6240777778,52.6845638889,609.6 + + + + + + EGRU229A LAKENHEATH + <table border="1" cellpadding="1" cellspacing="0" row_id="7839" txt_name="LAKENHEATH"><tr><td>A circle, 2.5 NM radius, centred at 522434N 0003340E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5610111111,52.4510112135,609.6 0.5547274249,52.450833553,609.6 0.5484974994,52.4503020916,609.6 0.5423746316,52.449421376,609.6 0.5364111949,52.4481989406,609.6 0.5306581878,52.4466452426,609.6 0.5251647946,52.4447735713,609.6 0.5199779625,52.4425999343,609.6 0.515141998,52.440142919,609.6 0.5106981874,52.4374235329,609.6 0.5066844433,52.4344650226,609.6 0.5031349815,52.4312926741,609.6 0.5000800299,52.4279335955,609.6 0.4975455726,52.4244164841,609.6 0.4955531305,52.4207713805,609.6 0.4941195818,52.417029411,609.6 0.4932570219,52.4132225209,609.6 0.4929726646,52.4093832018,609.6 0.4932687858,52.4055442135,609.6 0.494142709,52.4017383046,609.6 0.4955868334,52.3979979332,609.6 0.4975887035,52.3943549902,609.6 0.5001311201,52.3908405284,609.6 0.5031922911,52.3874844981,609.6 0.5067460207,52.3843154928,609.6 0.5107619357,52.3813605068,609.6 0.5152057463,52.3786447059,609.6 0.52003954,52.3761912149,609.6 0.5252221043,52.3740209211,609.6 0.530709278,52.3721522981,609.6 0.5364543259,52.3706012496,609.6 0.5424083345,52.3693809749,609.6 0.5485206266,52.3685018574,609.6 0.5547391888,52.3679713771,609.6 0.5610111111,52.3677940475,609.6 0.5672830334,52.3679713771,609.6 0.5735015956,52.3685018574,609.6 0.5796138877,52.3693809749,609.6 0.5855678964,52.3706012496,609.6 0.5913129442,52.3721522981,609.6 0.5968001179,52.3740209211,609.6 0.6019826822,52.3761912149,609.6 0.6068164759,52.3786447059,609.6 0.6112602866,52.3813605068,609.6 0.6152762015,52.3843154928,609.6 0.6188299311,52.3874844981,609.6 0.6218911021,52.3908405284,609.6 0.6244335187,52.3943549902,609.6 0.6264353888,52.3979979332,609.6 0.6278795132,52.4017383046,609.6 0.6287534364,52.4055442135,609.6 0.6290495576,52.4093832018,609.6 0.6287652003,52.4132225209,609.6 0.6279026404,52.417029411,609.6 0.6264690917,52.4207713805,609.6 0.6244766497,52.4244164841,609.6 0.6219421923,52.4279335955,609.6 0.6188872407,52.4312926741,609.6 0.615337779,52.4344650226,609.6 0.6113240349,52.4374235329,609.6 0.6068802242,52.440142919,609.6 0.6020442597,52.4425999343,609.6 0.5968574276,52.4447735713,609.6 0.5913640344,52.4466452426,609.6 0.5856110273,52.4481989406,609.6 0.5796475906,52.449421376,609.6 0.5735247228,52.4503020916,609.6 0.5672947973,52.450833553,609.6 0.5610111111,52.4510112135,609.6 + + + + + + EGRU229B LAKENHEATH RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7549" txt_name="LAKENHEATH RWY 06"><tr><td>522224N 0002916E -<br/>522251N 0002847E -<br/>522323N 0003004E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to<br/>522257N 0003034E -<br/>522224N 0002916E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.4878663333,52.3733966389,609.6 0.5093056111,52.3823689722,609.6 0.5062544483,52.3847182231,609.6 0.5034876038,52.3871958535,609.6 0.5010195,52.389789,609.6 0.4795878056,52.3808191667,609.6 0.4878663333,52.3733966389,609.6 + + + + + + EGRU229C LAKENHEATH RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7875" txt_name="LAKENHEATH RWY 24"><tr><td>522643N 0003803E -<br/>522617N 0003833E -<br/>522544N 0003716E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to<br/>522611N 0003646E -<br/>522643N 0003803E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6342404722,52.4453773611,609.6 0.6127547778,52.4364317778,609.6 0.6158060476,52.4340808663,609.6 0.6185718298,52.4316015868,609.6 0.6210377778,52.4290068611,609.6 0.6425311111,52.4379549167,609.6 0.6342404722,52.4453773611,609.6 + + + + + + EGRU230A WATTISHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="8099" txt_name="WATTISHAM"><tr><td>A circle, 2.5 NM radius, centred at 520737N 0005719E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9554138889,52.1686382148,609.6 0.9491700573,52.1684605475,609.6 0.9429796439,52.1679290655,609.6 0.9368956062,52.1670483157,609.6 0.9309699841,52.1658258326,609.6 0.9252534516,52.1642720733,609.6 0.91979488,52.1624003276,609.6 0.9146409182,52.1602266031,609.6 0.9098355913,52.1577694876,609.6 0.9054199238,52.155049989,609.6 0.9014315882,52.1520913543,609.6 0.8979045841,52.1489188703,609.6 0.8948689485,52.1455596457,609.6 0.8923505021,52.1420423786,609.6 0.8903706309,52.1383971107,609.6 0.8889461079,52.1346549692,609.6 0.8880889535,52.130847901,609.6 0.887806338,52.1270083989,609.6 0.8881005247,52.1231692242,609.6 0.8889688561,52.1193631272,609.6 0.8904037816,52.1156225676,609.6 0.8923929263,52.1119794383,609.6 0.8949192016,52.1084647939,609.6 0.8979609547,52.1051085866,609.6 0.9014921567,52.1019394118,609.6 0.9054826276,52.0989842656,609.6 0.9098982951,52.0962683158,609.6 0.9147014867,52.0938146888,609.6 0.9198512507,52.0916442735,609.6 0.9253037047,52.0897755451,609.6 0.9310124084,52.0882244085,609.6 0.9369287569,52.087004064,609.6 0.9430023922,52.0861248961,609.6 0.9491816284,52.0855943853,609.6 0.9554138889,52.0854170454,609.6 0.9616461494,52.0855943853,609.6 0.9678253856,52.0861248961,609.6 0.9738990208,52.087004064,609.6 0.9798153694,52.0882244085,609.6 0.9855240731,52.0897755451,609.6 0.9909765271,52.0916442735,609.6 0.996126291,52.0938146888,609.6 1.0009294826,52.0962683158,609.6 1.0053451502,52.0989842656,609.6 1.0093356211,52.1019394118,609.6 1.0128668231,52.1051085866,609.6 1.0159085762,52.1084647939,609.6 1.0184348515,52.1119794383,609.6 1.0204239962,52.1156225676,609.6 1.0218589216,52.1193631272,609.6 1.0227272531,52.1231692242,609.6 1.0230214398,52.1270083989,609.6 1.0227388243,52.130847901,609.6 1.0218816699,52.1346549692,609.6 1.0204571469,52.1383971107,609.6 1.0184772757,52.1420423786,609.6 1.0159588292,52.1455596457,609.6 1.0129231937,52.1489188703,609.6 1.0093961896,52.1520913543,609.6 1.005407854,52.155049989,609.6 1.0009921865,52.1577694876,609.6 0.9961868596,52.1602266031,609.6 0.9910328978,52.1624003276,609.6 0.9855743262,52.1642720733,609.6 0.9798577937,52.1658258326,609.6 0.9739321716,52.1670483157,609.6 0.9678481339,52.1679290655,609.6 0.9616577205,52.1684605475,609.6 0.9554138889,52.1686382148,609.6 + + + + + + EGRU230B WATTISHAM RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8117" txt_name="WATTISHAM RWY 05"><tr><td>520513N 0005340E -<br/>520537N 0005305E -<br/>520609N 0005402E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to<br/>520545N 0005438E -<br/>520513N 0005340E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.8945785833,52.0870821389,609.6 0.9104756667,52.09594825,609.6 0.9069544023,52.0980224587,609.6 0.9036846797,52.1002474723,609.6 0.9006835278,52.10261175,609.6 0.8847938611,52.0937486944,609.6 0.8945785833,52.0870821389,609.6 + + + + + + EGRU230C WATTISHAM RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7730" txt_name="WATTISHAM RWY 23"><tr><td>521004N 0010104E -<br/>520940N 0010139E -<br/>520905N 0010037E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to<br/>520929N 0010001E -<br/>521004N 0010104E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0178328056,52.1677814167,609.6 1.0003954167,52.1581005278,609.6 1.0039183892,52.1560243877,609.6 1.0071885817,52.1537973789,609.6 1.010189,52.1514311111,609.6 1.0276337778,52.1611149444,609.6 1.0178328056,52.1677814167,609.6 + + + + + + EGRU231A OLD BUCKENHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="7912" txt_name="OLD BUCKENHAM"><tr><td>A circle, 2 NM radius, centred at 522951N 0010307E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0520222222,52.5308612731,609.6 1.0464101911,52.5306847192,609.6 1.0408577828,52.5301569332,609.6 1.0354239821,52.5292835223,609.6 1.0301665059,52.5280737648,609.6 1.0251411855,52.5265405113,609.6 1.0204013713,52.5247000473,609.6 1.0159973633,52.5225719192,609.6 1.0119758757,52.5201787251,609.6 1.0083795406,52.5175458742,609.6 1.0052464557,52.5147013154,609.6 1.0026097816,52.5116752395,609.6 1.0004973925,52.5084997572,609.6 0.9989315839,52.5052085578,609.6 0.9979288402,52.5018365507,609.6 0.9974996651,52.4984194941,609.6 0.9976484753,52.494993616,609.6 0.9983735593,52.4915952294,609.6 0.9996671014,52.4882603475,609.6 1.00151527,52.4850243027,609.6 1.0038983689,52.4819213726,609.6 1.0067910512,52.4789844178,609.6 1.0101625908,52.476244535,609.6 1.0139772115,52.4737307285,609.6 1.0181944671,52.4714696049,609.6 1.0227696711,52.4694850923,609.6 1.0276543694,52.4677981888,609.6 1.032796852,52.4664267412,609.6 1.0381426984,52.4653852575,609.6 1.0436353506,52.4646847541,609.6 1.0492167076,52.4643326403,609.6 1.0548277368,52.4643326403,609.6 1.0604090939,52.4646847541,609.6 1.065901746,52.4653852575,609.6 1.0712475924,52.4664267412,609.6 1.0763900751,52.4677981888,609.6 1.0812747734,52.4694850923,609.6 1.0858499774,52.4714696049,609.6 1.090067233,52.4737307285,609.6 1.0938818536,52.476244535,609.6 1.0972533933,52.4789844178,609.6 1.1001460755,52.4819213726,609.6 1.1025291745,52.4850243027,609.6 1.104377343,52.4882603475,609.6 1.1056708852,52.4915952294,609.6 1.1063959692,52.494993616,609.6 1.1065447793,52.4984194941,609.6 1.1061156042,52.5018365507,609.6 1.1051128606,52.5052085578,609.6 1.1035470519,52.5084997572,609.6 1.1014346628,52.5116752395,609.6 1.0987979888,52.5147013154,609.6 1.0956649038,52.5175458742,609.6 1.0920685687,52.5201787251,609.6 1.0880470812,52.5225719192,609.6 1.0836430731,52.5247000473,609.6 1.0789032589,52.5265405113,609.6 1.0738779385,52.5280737648,609.6 1.0686204623,52.5292835223,609.6 1.0631866617,52.5301569332,609.6 1.0576342533,52.5306847192,609.6 1.0520222222,52.5308612731,609.6 + + + + + + EGRU231B OLD BUCKENHAM RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8036" txt_name="OLD BUCKENHAM RWY 02"><tr><td>522715N 0010159E -<br/>522726N 0010110E -<br/>522806N 0010133E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>522755N 0010223E -<br/>522715N 0010159E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0331583333,52.4542777778,609.6 1.0395878889,52.4651658333,609.6 1.0348536529,52.4659820364,609.6 1.0302589954,52.4670554677,609.6 1.0258412778,52.4683773889,609.6 1.0193194444,52.4573277778,609.6 1.0331583333,52.4542777778,609.6 + + + + + + EGRU231C OLD BUCKENHAM RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7915" txt_name="OLD BUCKENHAM RWY 20"><tr><td>523242N 0010416E -<br/>523231N 0010506E -<br/>523138N 0010435E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>523149N 0010345E -<br/>523242N 0010416E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.0711527778,52.5449833333,609.6 1.0624254444,52.5302505833,609.6 1.0672134848,52.5295449608,609.6 1.0718775255,52.5285787725,609.6 1.0763795,52.5273598889,609.6 1.0850166667,52.5419333333,609.6 1.0711527778,52.5449833333,609.6 + + + + + + EGRU231D OLD BUCKENHAM RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7756" txt_name="OLD BUCKENHAM RWY 07"><tr><td>522822N 0005900E -<br/>522851N 0005837E -<br/>522915N 0010000E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>522846N 0010023E -<br/>522822N 0005900E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9833472222,52.4727333333,609.6 1.0063476944,52.4793926667,609.6 1.003847467,52.4819797884,609.6 1.0017391739,52.4846939569,609.6 1.0000400278,52.4875130833,609.6 0.9770555556,52.4808583333,609.6 0.9833472222,52.4727333333,609.6 + + + + + + EGRU231E OLD BUCKENHAM RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7711" txt_name="OLD BUCKENHAM RWY 25"><tr><td>523120N 0010715E -<br/>523051N 0010737E -<br/>523027N 0010615E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>523057N 0010552E -<br/>523120N 0010715E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.1207472222,52.5223555556,609.6 1.0977450556,52.5157296667,609.6 1.1002399859,52.5131402516,609.6 1.1023418593,52.5104241196,609.6 1.1040336389,52.5076034167,609.6 1.12705,52.5142333333,609.6 1.1207472222,52.5223555556,609.6 + + + + + + EGRU231F OLD BUCKENHAM RWY 07L + <table border="1" cellpadding="1" cellspacing="0" row_id="7820" txt_name="OLD BUCKENHAM RWY 07L"><tr><td>522828N 0005916E -<br/>522857N 0005853E -<br/>522917N 0005959E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>522847N 0010021E -<br/>522828N 0005916E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.9878055556,52.4744638889,609.6 1.0059615,52.4797591944,609.6 1.0035164819,52.4823666245,609.6 1.0014662454,52.485097998,609.6 0.9998275556,52.4879310833,609.6 0.9814722222,52.4825777778,609.6 0.9878055556,52.4744638889,609.6 + + + + + + EGRU231G OLD BUCKENHAM RWY 25R + <table border="1" cellpadding="1" cellspacing="0" row_id="8119" txt_name="OLD BUCKENHAM RWY 25R"><tr><td>523122N 0010711E -<br/>523053N 0010734E -<br/>523030N 0010613E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to<br/>523059N 0010550E -<br/>523122N 0010711E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.1198027778,52.5228194444,609.6 1.0971755833,52.5162530833,609.6 1.0997504044,52.5136926291,609.6 1.1019361107,52.5110009461,609.6 1.1037149444,52.5081999722,609.6 1.1261416667,52.5147083333,609.6 1.1198027778,52.5228194444,609.6 + + + + + + EGRU232A NORWICH + <table border="1" cellpadding="1" cellspacing="0" row_id="7679" txt_name="NORWICH"><tr><td>A circle, 2.5 NM radius, centred at 524033N 0011658E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.2826638889,52.7175398849,609.6 1.2763419716,52.7173622309,609.6 1.2700741436,52.7168307887,609.6 1.2639140275,52.7159501052,609.6 1.2579143166,52.7147277146,609.6 1.252126321,52.713174074,609.6 1.2465995249,52.7113024726,609.6 1.2413811617,52.7091289177,609.6 1.236515808,52.7066719965,609.6 1.232045001,52.703952716,609.6 1.2280068838,52.7009943225,609.6 1.2244358797,52.6978221014,609.6 1.2213623995,52.6944631601,609.6 1.218812584,52.6909461951,609.6 1.2168080836,52.687301246,609.6 1.2153658776,52.6835594382,609.6 1.2144981329,52.6797527158,609.6 1.2142121053,52.675913569,609.6 1.2145100826,52.6720747562,609.6 1.2153893702,52.6682690245,609.6 1.216842319,52.6645288303,609.6 1.2188563964,52.6608860629,609.6 1.2214142969,52.6573717732,609.6 1.2244940948,52.6540159098,609.6 1.2280694342,52.6508470644,609.6 1.2321097566,52.6478922294,609.6 1.2365805636,52.645176569,609.6 1.2414437122,52.6427232063,609.6 1.2466577401,52.6405530271,609.6 1.2521782185,52.6386845036,609.6 1.2579581291,52.6371335382,609.6 1.263948263,52.6359133293,609.6 1.2700976362,52.6350342594,609.6 1.2763539214,52.634503808,609.6 1.2826638889,52.6343264879,609.6 1.2889738564,52.634503808,609.6 1.2952301415,52.6350342594,609.6 1.3013795148,52.6359133293,609.6 1.3073696486,52.6371335382,609.6 1.3131495593,52.6386845036,609.6 1.3186700377,52.6405530271,609.6 1.3238840656,52.6427232063,609.6 1.3287472142,52.645176569,609.6 1.3332180212,52.6478922294,609.6 1.3372583436,52.6508470644,609.6 1.3408336829,52.6540159098,609.6 1.3439134809,52.6573717732,609.6 1.3464713814,52.6608860629,609.6 1.3484854587,52.6645288303,609.6 1.3499384076,52.6682690245,609.6 1.3508176951,52.6720747562,609.6 1.3511156725,52.675913569,609.6 1.3508296449,52.6797527158,609.6 1.3499619002,52.6835594382,609.6 1.3485196942,52.687301246,609.6 1.3465151938,52.6909461951,609.6 1.3439653783,52.6944631601,609.6 1.3408918981,52.6978221014,609.6 1.337320894,52.7009943225,609.6 1.3332827768,52.703952716,609.6 1.3288119698,52.7066719965,609.6 1.323946616,52.7091289177,609.6 1.3187282529,52.7113024726,609.6 1.3132014568,52.713174074,609.6 1.3074134611,52.7147277146,609.6 1.3014137503,52.7159501052,609.6 1.2952536342,52.7168307887,609.6 1.2889858062,52.7173622309,609.6 1.2826638889,52.7175398849,609.6 + + + + + + EGRU232B NORWICH RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7874" txt_name="NORWICH RWY 09"><tr><td>524015N 0011143E -<br/>524047N 0011142E -<br/>524048N 0011252E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to<br/>524015N 0011253E -<br/>524015N 0011143E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.1952277778,52.6707472222,609.6 1.2147172778,52.6709072222,609.6 1.2142956962,52.6738970556,609.6 1.2142297104,52.6768975825,609.6 1.2145197222,52.6798931944,609.6 1.1950472222,52.6797333333,609.6 1.1952277778,52.6707472222,609.6 + + + + + + EGRU232C NORWICH RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7838" txt_name="NORWICH RWY 27"><tr><td>524052N 0012212E -<br/>524019N 0012213E -<br/>524019N 0012103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to<br/>524051N 0012102E -<br/>524052N 0012212E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.3700972222,52.6810555556,609.6 1.3506258889,52.68092125,609.6 1.3510383033,52.6779309394,609.6 1.3510950081,52.6749303384,609.6 1.3507957778,52.6719350556,609.6 1.3702833333,52.6720694444,609.6 1.3700972222,52.6810555556,609.6 + + + + + + EGRU233A CHETWYND + <table border="1" cellpadding="1" cellspacing="0" row_id="8501" txt_name="CHETWYND"><tr><td>A circle, 2 NM radius, centred at 524842N 0022425W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4070333333,52.8448400548,609.6 -2.4126857617,52.8446635088,609.6 -2.4182781367,52.8441357465,609.6 -2.4237510472,52.8432623748,609.6 -2.4290463597,52.842052672,609.6 -2.4341078399,52.8405194884,609.6 -2.4388817526,52.8386791092,609.6 -2.4433174353,52.83655108,609.6 -2.4473678374,52.8341579987,609.6 -2.4509900203,52.8315252736,609.6 -2.4541456127,52.8286808528,609.6 -2.4568012165,52.8256549258,609.6 -2.4589287581,52.8224796025,609.6 -2.4605057833,52.8191885707,609.6 -2.4615156908,52.815816738,609.6 -2.4619479035,52.8123998614,609.6 -2.4617979748,52.8089741667,609.6 -2.4610676306,52.8055759649,609.6 -2.4597647448,52.8022412674,609.6 -2.4579032504,52.7990054042,609.6 -2.4555029865,52.7959026509,609.6 -2.452589484,52.7929658657,609.6 -2.4491936904,52.7902261431,609.6 -2.4453516401,52.7877124853,609.6 -2.4411040699,52.7854514968,609.6 -2.4364959876,52.783467104,609.6 -2.4315761948,52.781780303,609.6 -2.4263967722,52.7804089394,609.6 -2.4210125304,52.7793675197,609.6 -2.4154804323,52.7786670595,609.6 -2.4098589945,52.7783149675,609.6 -2.4042076722,52.7783149675,609.6 -2.3985862344,52.7786670595,609.6 -2.3930541363,52.7793675197,609.6 -2.3876698944,52.7804089394,609.6 -2.3824904719,52.781780303,609.6 -2.3775706791,52.783467104,609.6 -2.3729625967,52.7854514968,609.6 -2.3687150266,52.7877124853,609.6 -2.3648729763,52.7902261431,609.6 -2.3614771827,52.7929658657,609.6 -2.3585636801,52.7959026509,609.6 -2.3561634163,52.7990054042,609.6 -2.3543019219,52.8022412674,609.6 -2.3529990361,52.8055759649,609.6 -2.3522686919,52.8089741667,609.6 -2.3521187632,52.8123998614,609.6 -2.3525509758,52.815816738,609.6 -2.3535608834,52.8191885707,609.6 -2.3551379086,52.8224796025,609.6 -2.3572654502,52.8256549258,609.6 -2.359921054,52.8286808528,609.6 -2.3630766464,52.8315252736,609.6 -2.3666988293,52.8341579987,609.6 -2.3707492314,52.83655108,609.6 -2.3751849141,52.8386791092,609.6 -2.3799588268,52.8405194884,609.6 -2.385020307,52.842052672,609.6 -2.3903156195,52.8432623748,609.6 -2.39578853,52.8441357465,609.6 -2.4013809049,52.8446635088,609.6 -2.4070333333,52.8448400548,609.6 + + + + + + EGRU234A HONINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="12076" txt_name="HONINGTON"><tr><td>A circle, 2 NM radius, centred at 522036N 0004648E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.78,52.3766204797,609.6 0.7744075413,52.376443922,609.6 0.7688744967,52.3759161243,609.6 0.7634596447,52.375042694,609.6 0.7582205001,52.3738329095,609.6 0.7532126991,52.3722996215,609.6 0.7484894056,52.3704591158,609.6 0.7441007439,52.3683309388,609.6 0.7400932655,52.3659376891,609.6 0.7365094537,52.3633047762,609.6 0.7333872738,52.3604601494,609.6 0.7307597713,52.357434,609.6 0.7286547238,52.3542584394,609.6 0.7270943498,52.3509671575,609.6 0.7260950772,52.3475950644,609.6 0.7256673739,52.3441779193,609.6 0.7258156423,52.3407519509,609.6 0.726538178,52.3373534732,609.6 0.7278271932,52.3340185006,609.6 0.7296689055,52.3307823664,609.6 0.7320436881,52.3276793494,609.6 0.734926283,52.3247423112,609.6 0.7382860716,52.3220023496,609.6 0.7420874025,52.31948847,609.6 0.7462899707,52.3172272799,609.6 0.750849245,52.3152427085,609.6 0.7557169399,52.3135557546,609.6 0.7608415249,52.3121842658,609.6 0.7661687685,52.3111427505,609.6 0.7716423088,52.3104422259,609.6 0.7772042465,52.3100901013,609.6 0.7827957535,52.3100901013,609.6 0.7883576912,52.3104422259,609.6 0.7938312315,52.3111427505,609.6 0.7991584751,52.3121842658,609.6 0.8042830601,52.3135557546,609.6 0.809150755,52.3152427085,609.6 0.8137100293,52.3172272799,609.6 0.8179125975,52.31948847,609.6 0.8217139284,52.3220023496,609.6 0.825073717,52.3247423112,609.6 0.8279563119,52.3276793494,609.6 0.8303310945,52.3307823664,609.6 0.8321728068,52.3340185006,609.6 0.833461822,52.3373534732,609.6 0.8341843577,52.3407519509,609.6 0.8343326261,52.3441779193,609.6 0.8339049228,52.3475950644,609.6 0.8329056502,52.3509671575,609.6 0.8313452762,52.3542584394,609.6 0.8292402287,52.357434,609.6 0.8266127262,52.3604601494,609.6 0.8234905463,52.3633047762,609.6 0.8199067345,52.3659376891,609.6 0.8158992561,52.3683309388,609.6 0.8115105944,52.3704591158,609.6 0.8067873009,52.3722996215,609.6 0.8017794999,52.3738329095,609.6 0.7965403553,52.375042694,609.6 0.7911255033,52.3759161243,609.6 0.7855924587,52.376443922,609.6 0.78,52.3766204797,609.6 + + + + + + EGRU234B HONINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="12077" txt_name="HONINGTON"><tr><td>521947N 0004055E -<br/>522019N 0004047E -<br/>522035N 0004332E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to<br/>522003N 0004340E -<br/>521947N 0004055E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.6818130278,52.3296939722,609.6 0.7278162222,52.3340415556,609.6 0.7266595214,52.3369605969,609.6 0.7259369978,52.3399316222,609.6 0.7256546111,52.3429304444,609.6 0.6795900833,52.3385770556,609.6 0.6818130278,52.3296939722,609.6 + + + + + + EGRU234C HONINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="12078" txt_name="HONINGTON"><tr><td>522121N 0005151E -<br/>522049N 0005159E -<br/>522039N 0005004E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to<br/>522110N 0004955E -<br/>522121N 0005151E <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.8642396389,52.3559142222,609.6 0.8320553889,52.3529141111,609.6 0.8332521006,52.3500010766,609.6 0.8340149861,52.3470338347,609.6 0.8343379167,52.3440365556,609.6 0.8664634722,52.3470311667,609.6 0.8642396389,52.3559142222,609.6 + + + + + + EGRU235 HMP BEDFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14122" txt_name="HMP BEDFORD"><tr><td>520840N 0002812W -<br/>520836N 0002756W -<br/>520822N 0002743W -<br/>520804N 0002758W -<br/>520807N 0002824W -<br/>520815N 0002840W -<br/>520835N 0002832W -<br/>520840N 0002812W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 115 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4699694444,52.1445194444,182.88 -0.4754777778,52.1431472222,182.88 -0.4778222222,52.1376055556,182.88 -0.473425,52.1351944444,182.88 -0.4660722222,52.1345444444,182.88 -0.4620055556,52.1395611111,182.88 -0.4655805556,52.1431944444,182.88 -0.4699694444,52.1445194444,182.88 + + + + + + EGRU236 HMP BIRMINGHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="14101" txt_name="HMP BIRMINGHAM"><tr><td>522954N 0015626W -<br/>522952N 0015553W -<br/>522944N 0015547W -<br/>522925N 0015547W -<br/>522918N 0015558W -<br/>522917N 0015633W -<br/>522944N 0015648W -<br/>522954N 0015626W <br/>Upper limit: 900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 483 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9406583333,52.4983111111,274.32 -1.9467111111,52.4955527778,274.32 -1.9424222222,52.4879805556,274.32 -1.9326861111,52.4882194444,274.32 -1.9296444444,52.4903972222,274.32 -1.9297361111,52.4954916667,274.32 -1.9314527778,52.4976833333,274.32 -1.9406583333,52.4983111111,274.32 + + + + + + EGRU237 HMP BURE + <table border="1" cellpadding="1" cellspacing="0" row_id="14116" txt_name="HMP BURE"><tr><td>524549N 0012029E -<br/>524552N 0012052E -<br/>524537N 0012123E -<br/>524511N 0012049E -<br/>524532N 0012007E -<br/>524549N 0012029E <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 77 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.3413777778,52.763725,152.4 1.3352138889,52.7589055556,152.4 1.3470583333,52.7531694444,152.4 1.3564444444,52.7601555556,152.4 1.3476527778,52.7643277778,152.4 1.3413777778,52.763725,152.4 + + + + + + EGRU238 HMP DOVEGATE + <table border="1" cellpadding="1" cellspacing="0" row_id="14130" txt_name="HMP DOVEGATE"><tr><td>525234N 0014708W -<br/>525234N 0014639W -<br/>525215N 0014608W -<br/>525150N 0014649W -<br/>525212N 0014724W -<br/>525226N 0014723W -<br/>525234N 0014708W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 243 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7855305556,52.876175,213.36 -1.7896972222,52.8737777778,213.36 -1.7901194444,52.869925,213.36 -1.7803777778,52.8639833333,213.36 -1.7689,52.8708833333,213.36 -1.7776138889,52.8761416667,213.36 -1.7855305556,52.876175,213.36 + + + + + + EGRU239 HMP DRAKE HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14147" txt_name="HMP DRAKE HALL"><tr><td>525309N 0021429W -<br/>525249N 0021352W -<br/>525224N 0021421W -<br/>525223N 0021445W -<br/>525241N 0021503W -<br/>525255N 0021453W -<br/>525309N 0021429W <br/>Upper limit: 800 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 347 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2413305556,52.8857111111,243.84 -2.2480138889,52.8818361111,243.84 -2.2509111111,52.878175,243.84 -2.2458916667,52.8730916667,243.84 -2.2392972222,52.8733055556,243.84 -2.23105,52.8802388889,243.84 -2.2413305556,52.8857111111,243.84 + + + + + + EGRU240 HMP FEATHERSTONE/BRINSFORD/OAKWOOD + <table border="1" cellpadding="1" cellspacing="0" row_id="14126" txt_name="HMP FEATHERSTONE/BRINSFORD/OAKWOOD"><tr><td>523917N 0020718W -<br/>523923N 0020623W -<br/>523849N 0020555W -<br/>523821N 0020609W -<br/>523826N 0020658W -<br/>523841N 0020716W -<br/>523917N 0020718W <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 393 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1215583333,52.6548,243.84 -2.1211027778,52.6446611111,243.84 -2.1161916667,52.6406138889,243.84 -2.1026027778,52.6392138889,243.84 -2.0985861111,52.6469722222,243.84 -2.1064611111,52.6564722222,243.84 -2.1215583333,52.6548,243.84 + + + + + + EGRU241 HMP FIVE WELLS + <table border="1" cellpadding="1" cellspacing="0" row_id="14109" txt_name="HMP FIVE WELLS"><tr><td>521728N 0004128W -<br/>521727N 0004101W -<br/>521710N 0004054W -<br/>521646N 0004102W -<br/>521645N 0004141W -<br/>521658N 0004205W -<br/>521714N 0004205W -<br/>521728N 0004128W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 226 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6910527778,52.290975,213.36 -0.7013305556,52.2872861111,213.36 -0.7012527778,52.2828583333,213.36 -0.6947,52.2791583333,213.36 -0.6839666667,52.279475,213.36 -0.6817027778,52.2861777778,213.36 -0.6836805556,52.2908,213.36 -0.6910527778,52.290975,213.36 + + + + + + EGRU242 HMP FOSSE WAY + <table border="1" cellpadding="1" cellspacing="0" row_id="14115" txt_name="HMP FOSSE WAY"><tr><td>523531N 0010859W -<br/>523528N 0010812W -<br/>523443N 0010815W -<br/>523439N 0010853W -<br/>523446N 0010924W -<br/>523531N 0010859W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 298 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1498138889,52.5918888889,213.36 -1.1565666667,52.5795416667,213.36 -1.1481777778,52.5774944444,213.36 -1.1375694444,52.5785861111,213.36 -1.136575,52.5911527778,213.36 -1.1498138889,52.5918888889,213.36 + + + + + + EGRU243 HMP FOSTON HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14117" txt_name="HMP FOSTON HALL"><tr><td>525313N 0014400W -<br/>525314N 0014325W -<br/>525303N 0014256W -<br/>525237N 0014314W -<br/>525237N 0014357W -<br/>525313N 0014400W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 223 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.733425,52.8869805556,213.36 -1.732525,52.8769722222,213.36 -1.7205361111,52.8770083333,213.36 -1.715675,52.8840833333,213.36 -1.7236166667,52.8872555556,213.36 -1.733425,52.8869805556,213.36 + + + + + + EGRU244 HMP GARTREE + <table border="1" cellpadding="1" cellspacing="0" row_id="14105" txt_name="HMP GARTREE"><tr><td>523004N 0005752W -<br/>522959N 0005714W -<br/>522931N 0005708W -<br/>522921N 0005801W -<br/>522945N 0005814W -<br/>523004N 0005752W <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 398 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.964475,52.5010833333,243.84 -0.9705583333,52.4957944444,243.84 -0.9670111111,52.4890361111,243.84 -0.9521666667,52.49195,243.84 -0.9539333333,52.4998388889,243.84 -0.964475,52.5010833333,243.84 + + + + + + EGRU245 HMP HEWELL + <table border="1" cellpadding="1" cellspacing="0" row_id="14104" txt_name="HMP HEWELL"><tr><td>521951N 0015926W -<br/>521935N 0015833W -<br/>521911N 0015853W -<br/>521911N 0015919W -<br/>521917N 0015936W -<br/>521930N 0015948W -<br/>521951N 0015926W <br/>Upper limit: 900 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 443 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9904305556,52.3309666667,274.32 -1.9966583333,52.3249638889,274.32 -1.9934444444,52.3214833333,274.32 -1.9885444444,52.3197611111,274.32 -1.9815083333,52.3198361111,274.32 -1.9757583333,52.3262611111,274.32 -1.9904305556,52.3309666667,274.32 + + + + + + EGRU246 HMP HIGHPOINT + <table border="1" cellpadding="1" cellspacing="0" row_id="14125" txt_name="HMP HIGHPOINT"><tr><td>520847N 0003034E -<br/>520845N 0003109E -<br/>520801N 0003134E -<br/>520749N 0003019E -<br/>520822N 0003003E -<br/>520847N 0003034E <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 390 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.5095194444,52.1464944444,243.84 0.5008166667,52.1393277778,243.84 0.5051555556,52.1304,243.84 0.5260694444,52.1337222222,243.84 0.5192861111,52.1459222222,243.84 0.5095194444,52.1464944444,243.84 + + + + + + EGRU247 HMP LEICESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="14123" txt_name="HMP LEICESTER"><tr><td>523755N 0010756W -<br/>523744N 0010724W -<br/>523728N 0010735W -<br/>523721N 0010753W -<br/>523730N 0010818W -<br/>523749N 0010821W -<br/>523755N 0010756W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 215 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1321138889,52.6320527778,213.36 -1.1391555556,52.63035,213.36 -1.1383638889,52.6250333333,213.36 -1.1312555556,52.6224777778,213.36 -1.126375,52.6244472222,213.36 -1.1232083333,52.6289055556,213.36 -1.1321138889,52.6320527778,213.36 + + + + + + EGRU248 HMP LITTLEHEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14076" txt_name="HMP LITTLEHEY"><tr><td>521707N 0001916W -<br/>521706N 0001824W -<br/>521656N 0001811W -<br/>521637N 0001817W -<br/>521627N 0001846W -<br/>521633N 0001920W -<br/>521648N 0001924W -<br/>521707N 0001916W <br/>Upper limit: 600 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 173 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3211638889,52.2851944444,182.88 -0.3232416667,52.2799638889,182.88 -0.3221722222,52.2757138889,182.88 -0.31275,52.2740583333,182.88 -0.3047,52.2770305556,182.88 -0.3030472222,52.2820888889,182.88 -0.3065888889,52.2849,182.88 -0.3211638889,52.2851944444,182.88 + + + + + + EGRU249 HMP LONG LARTIN + <table border="1" cellpadding="1" cellspacing="0" row_id="14068" txt_name="HMP LONG LARTIN"><tr><td>520649N 0015133W -<br/>520643N 0015034W -<br/>520609N 0015055W -<br/>520616N 0015158W -<br/>520649N 0015133W <br/>Upper limit: 600 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 160 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8592277778,52.1137055556,182.88 -1.8661638889,52.1045055556,182.88 -1.8485638889,52.1024805556,182.88 -1.8427472222,52.1118416667,182.88 -1.8592277778,52.1137055556,182.88 + + + + + + EGRU250 HMP NORWICH + <table border="1" cellpadding="1" cellspacing="0" row_id="14103" txt_name="HMP NORWICH"><tr><td>523836N 0011852E -<br/>523838N 0011915E -<br/>523811N 0011938E -<br/>523801N 0011938E -<br/>523748N 0011855E -<br/>523753N 0011845E -<br/>523821N 0011823E -<br/>523836N 0011852E <br/>Upper limit: 600 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Norwich Airport (FRZ - EGRU232A) and HMPPS.<br/>Contact online:<br/>https://www.norwichairport.co.uk/airfield-pilot-information/<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 160 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.3143916667,52.643425,182.88 1.306325,52.6392277778,182.88 1.3124305556,52.6312888889,182.88 1.315325,52.6298722222,182.88 1.3273166667,52.6334861111,182.88 1.3273055556,52.6363027778,182.88 1.3208805556,52.6439222222,182.88 1.3143916667,52.643425,182.88 + + + + + + EGRU251 HMP NOTTINGHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="14073" txt_name="HMP NOTTINGHAM"><tr><td>525921N 0010935W -<br/>525925N 0010857W -<br/>525856N 0010848W -<br/>525850N 0010906W -<br/>525848N 0010942W -<br/>525905N 0010948W -<br/>525915N 0010946W -<br/>525921N 0010935W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 255 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1597333333,52.9892694444,213.36 -1.1628611111,52.9873611111,213.36 -1.1632805556,52.9847805556,213.36 -1.1615972222,52.9799111111,213.36 -1.1516527778,52.9804916667,213.36 -1.1467583333,52.9822333333,213.36 -1.1490861111,52.9902666667,213.36 -1.1597333333,52.9892694444,213.36 + + + + + + EGRU252 HMP PETERBOROUGH + <table border="1" cellpadding="1" cellspacing="0" row_id="14145" txt_name="HMP PETERBOROUGH"><tr><td>523529N 0001553W -<br/>523535N 0001524W -<br/>523459N 0001501W -<br/>523451N 0001534W -<br/>523458N 0001559W -<br/>523506N 0001602W -<br/>523520N 0001602W -<br/>523529N 0001553W <br/>Upper limit: 500 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 62 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2647388889,52.5912555556,152.4 -0.2671416667,52.5888777778,152.4 -0.2673222222,52.5848972222,152.4 -0.2662805556,52.5826527778,152.4 -0.259575,52.5809666667,152.4 -0.2503805556,52.5831861111,152.4 -0.2566833333,52.5931027778,152.4 -0.2647388889,52.5912555556,152.4 + + + + + + EGRU253 HMP RYE HILL/OLNEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14099" txt_name="HMP RYE HILL/OLNEY"><tr><td>522004N 0011457W -<br/>522005N 0011435W -<br/>521956N 0011413W -<br/>521948N 0011408W -<br/>521937N 0011406W -<br/>521925N 0011421W -<br/>521919N 0011455W -<br/>521920N 0011535W -<br/>522000N 0011513W -<br/>522004N 0011457W <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 361 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2492583333,52.3345611111,243.84 -1.2535833333,52.3334,243.84 -1.2598194444,52.3222833333,243.84 -1.24855,52.3219944444,243.84 -1.2393027778,52.3234916667,243.84 -1.2349888889,52.3268305556,243.84 -1.2354277778,52.3299555556,243.84 -1.2369777778,52.3322388889,243.84 -1.2430083333,52.3347111111,243.84 -1.2492583333,52.3345611111,243.84 + + + + + + EGRU254 HMP STAFFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="14100" txt_name="HMP STAFFORD"><tr><td>524854N 0020734W -<br/>524902N 0020643W -<br/>524841N 0020635W -<br/>524828N 0020639W -<br/>524820N 0020720W -<br/>524854N 0020734W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 267 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1262083333,52.8149555556,213.36 -2.1221472222,52.8056,213.36 -2.1107027778,52.8076833333,213.36 -2.1095888889,52.811475,213.36 -2.1118638889,52.8170972222,213.36 -2.1262083333,52.8149555556,213.36 + + + + + + EGRU255 HMP STOCKEN + <table border="1" cellpadding="1" cellspacing="0" row_id="14108" txt_name="HMP STOCKEN"><tr><td>524512N 0003449W -<br/>524513N 0003414W -<br/>524450N 0003403W -<br/>524434N 0003430W -<br/>524429N 0003454W -<br/>524440N 0003514W -<br/>524449N 0003518W -<br/>524504N 0003516W -<br/>524512N 0003449W <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 371 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5802055556,52.7534361111,243.84 -0.5877777778,52.75105,243.84 -0.5882805556,52.7468638889,243.84 -0.5872194444,52.7445277778,243.84 -0.5816472222,52.7414027778,243.84 -0.5750555556,52.7427916667,243.84 -0.5675138889,52.74725,243.84 -0.570525,52.7535111111,243.84 -0.5802055556,52.7534361111,243.84 + + + + + + EGRU256 HMP STOKE HEATH + <table border="1" cellpadding="1" cellspacing="0" row_id="14059" txt_name="HMP STOKE HEATH"><tr><td>525231N 0023138W -<br/>525224N 0023119W -<br/>525231N 0023107W -<br/>525216N 0023045W -<br/>525202N 0023043W -<br/>525157N 0023052W -<br/>525142N 0023059W -<br/>525152N 0023157W -<br/>525231N 0023138W <br/>Upper limit: 700 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by RAF Shawbury (Ternhill FRZ - EGRU206A) and HMPPS.<br/>Contact: RAF Shawbury Station Ops 01939-250341 ext 7163 shy-ops@mod.gov.uk<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 269 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5272138889,52.8752055556,213.36 -2.5324694444,52.8644888889,213.36 -2.5165222222,52.8617055556,213.36 -2.5145416667,52.865825,213.36 -2.5119222222,52.8672861111,213.36 -2.5124138889,52.871175,213.36 -2.5187416667,52.8752555556,213.36 -2.5219416667,52.8734138889,213.36 -2.5272138889,52.8752055556,213.36 + + + + + + EGRU257 HMP SWINFEN HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14094" txt_name="HMP SWINFEN HALL"><tr><td>523936N 0014816W -<br/>523921N 0014741W -<br/>523908N 0014741W -<br/>523849N 0014810W -<br/>523857N 0014834W -<br/>523910N 0014858W -<br/>523936N 0014816W <br/>Upper limit: 800 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 309 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.8045694444,52.6599611111,243.84 -1.8159944444,52.6529083333,243.84 -1.8095166667,52.6490972222,243.84 -1.8028055556,52.6468833333,243.84 -1.794625,52.6522055556,243.84 -1.7946388889,52.6558527778,243.84 -1.8045694444,52.6599611111,243.84 + + + + + + EGRU258 HMP WARREN HILL + <table border="1" cellpadding="1" cellspacing="0" row_id="14152" txt_name="HMP WARREN HILL"><tr><td>520356N 0012736E -<br/>520335N 0012812E -<br/>520319N 0012809E -<br/>520307N 0012727E -<br/>520333N 0012659E -<br/>520356N 0012736E <br/>Upper limit: 500 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 59 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +1.4600444444,52.0655388889,152.4 1.449675,52.0590805556,152.4 1.4574888889,52.0519277778,152.4 1.4692555556,52.0552388889,152.4 1.4700805556,52.0596166667,152.4 1.4600444444,52.0655388889,152.4 + + + + + + EGRU259 HMP WAYLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="14074" txt_name="HMP WAYLAND"><tr><td>523337N 0005103E -<br/>523337N 0005158E -<br/>523256N 0005158E -<br/>523256N 0005109E -<br/>523313N 0005056E -<br/>523337N 0005103E <br/>Upper limit: 600 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 189 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.8507277778,52.5603666667,182.88 0.8488444444,52.5535222222,182.88 0.85245,52.5489833333,182.88 0.8659805556,52.5489666667,182.88 0.86615,52.5603555556,182.88 0.8507277778,52.5603666667,182.88 + + + + + + EGRU260 HMP WHATTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14119" txt_name="HMP WHATTON"><tr><td>525709N 0005519W -<br/>525708N 0005442W -<br/>525710N 0005428W -<br/>525659N 0005406W -<br/>525634N 0005402W -<br/>525638N 0005523W -<br/>525709N 0005519W <br/>Upper limit: 500 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 87 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9219444444,52.9525027778,152.4 -0.9229722222,52.9438333333,152.4 -0.900525,52.9426555556,152.4 -0.9016,52.94975,152.4 -0.9076666667,52.9528916667,152.4 -0.9117305556,52.9522305556,152.4 -0.9219444444,52.9525027778,152.4 + + + + + + EGRU261 HMP WHITEMOOR + <table border="1" cellpadding="1" cellspacing="0" row_id="14070" txt_name="HMP WHITEMOOR"><tr><td>523445N 0000411E -<br/>523456N 0000509E -<br/>523421N 0000527E -<br/>523410N 0000430E -<br/>523445N 0000411E <br/>Upper limit: 500 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 17 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +0.0698444444,52.5791083333,152.4 0.0748722222,52.5693833333,152.4 0.0908222222,52.5725166667,152.4 0.0857444444,52.5822833333,152.4 0.0698444444,52.5791083333,152.4 + + + + + + EGRU262 HMP WOODHILL + <table border="1" cellpadding="1" cellspacing="0" row_id="14086" txt_name="HMP WOODHILL"><tr><td>520113N 0004826W -<br/>520038N 0004752W -<br/>520021N 0004838W -<br/>520056N 0004913W -<br/>520113N 0004826W <br/>Upper limit: 900 FT MSL<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 401 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.807125,52.0203222222,274.32 -0.8203583333,52.0155555556,274.32 -0.8106138889,52.0057194444,274.32 -0.7978666667,52.0106333333,274.32 -0.807125,52.0203222222,274.32 + + + + + + EGRU301A VALLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="8123" txt_name="VALLEY"><tr><td>A circle, 2.5 NM radius, centred at 531453N 0043207W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: 0 FT SFC<br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5353333333,53.2897691896,609.6 -4.5417394023,53.2895915492,609.6 -4.5480906587,53.2890601481,609.6 -4.5543327631,53.2881795327,609.6 -4.5604123179,53.2869572374,609.6 -4.5662773276,53.2854037189,609.6 -4.5718776474,53.2835322662,609.6 -4.5771654137,53.281358886,609.6 -4.5820954562,53.2789021651,609.6 -4.5866256844,53.2761831096,609.6 -4.5907174486,53.273224965,609.6 -4.5943358686,53.2700530154,609.6 -4.597450131,53.2666943668,609.6 -4.6000337501,53.2631777142,609.6 -4.6020647903,53.2595330952,609.6 -4.6035260505,53.2557916327,609.6 -4.6044052057,53.2519852685,609.6 -4.604694908,53.2481464901,609.6 -4.6043928434,53.2443080527,609.6 -4.6035017468,53.2405027001,609.6 -4.6020293729,53.2367628853,609.6 -4.599988425,53.2331204938,609.6 -4.5973964418,53.2296065728,609.6 -4.5942756435,53.2262510669,609.6 -4.5906527385,53.2230825641,609.6 -4.5865586931,53.2201280529,609.6 -4.5820284648,53.2174126938,609.6 -4.5771007037,53.2149596063,609.6 -4.5718174223,53.2127896729,609.6 -4.5662236383,53.2109213629,609.6 -4.5603669927,53.209370576,609.6 -4.5542973456,53.2081505083,609.6 -4.548066355,53.2072715406,609.6 -4.5417270399,53.2067411509,609.6 -4.5353333333,53.2065638516,609.6 -4.5289396267,53.2067411509,609.6 -4.5226003117,53.2072715406,609.6 -4.5163693211,53.2081505083,609.6 -4.510299674,53.209370576,609.6 -4.5044430283,53.2109213629,609.6 -4.4988492444,53.2127896729,609.6 -4.493565963,53.2149596063,609.6 -4.4886382018,53.2174126938,609.6 -4.4841079736,53.2201280529,609.6 -4.4800139281,53.2230825641,609.6 -4.4763910232,53.2262510669,609.6 -4.4732702249,53.2296065728,609.6 -4.4706782417,53.2331204938,609.6 -4.4686372938,53.2367628853,609.6 -4.4671649199,53.2405027001,609.6 -4.4662738233,53.2443080527,609.6 -4.4659717587,53.2481464901,609.6 -4.4662614609,53.2519852685,609.6 -4.4671406162,53.2557916327,609.6 -4.4686018763,53.2595330952,609.6 -4.4706329166,53.2631777142,609.6 -4.4732165356,53.2666943668,609.6 -4.4763307981,53.2700530154,609.6 -4.4799492181,53.273224965,609.6 -4.4840409822,53.2761831096,609.6 -4.4885712105,53.2789021651,609.6 -4.4935012529,53.281358886,609.6 -4.4987890193,53.2835322662,609.6 -4.504389339,53.2854037189,609.6 -4.5102543488,53.2869572374,609.6 -4.5163339036,53.2881795327,609.6 -4.5225760079,53.2890601481,609.6 -4.5289272644,53.2895915492,609.6 -4.5353333333,53.2897691896,609.6 + + + + + + EGRU301B VALLEY RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="7522" txt_name="VALLEY RWY 01"><tr><td>531154N 0043228W -<br/>531158N 0043322W -<br/>531229N 0043316W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to<br/>531224N 0043223W -<br/>531154N 0043228W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5412361111,53.1983583333,609.6 -4.5397092778,53.2066468056,609.6 -4.5446913844,53.2069446068,609.6 -4.5496247792,53.2074573908,609.6 -4.5544837778,53.2081825,609.6 -4.5561083333,53.1993472222,609.6 -4.5412361111,53.1983583333,609.6 + + + + + + EGRU301C VALLEY RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="8009" txt_name="VALLEY RWY 19"><tr><td>531810N 0043213W -<br/>531806N 0043120W -<br/>531721N 0043128W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to<br/>531723N 0043222W -<br/>531810N 0043213W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5370638889,53.3026916667,609.6 -4.5394639444,53.2896954167,609.6 -4.5344489699,53.2897658191,609.6 -4.5294386237,53.2896188347,609.6 -4.5244591389,53.28925525,609.6 -4.5221555556,53.3017055556,609.6 -4.5370638889,53.3026916667,609.6 + + + + + + EGRU301D VALLEY RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="7510" txt_name="VALLEY RWY 13"><tr><td>531646N 0043630W -<br/>531711N 0043555W -<br/>531642N 0043459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to<br/>531618N 0043534W -<br/>531646N 0043630W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6082879167,53.2794899167,609.6 -4.5927136389,53.2715534167,609.6 -4.5897540887,53.2739730646,609.6 -4.5865109682,53.2762584688,609.6 -4.5830011389,53.2783977222,609.6 -4.5985659167,53.2863302778,609.6 -4.6082879167,53.2794899167,609.6 + + + + + + EGRU301E VALLEY RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="7931" txt_name="VALLEY RWY 31"><tr><td>531253N 0042730W -<br/>531228N 0042805W -<br/>531305N 0042916W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to<br/>531329N 0042841W -<br/>531253N 0042730W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4584117778,53.2147212778,609.6 -4.4780087222,53.2247583056,609.6 -4.4809704688,53.2223411037,609.6 -4.4842144577,53.2200582086,609.6 -4.4877238056,53.2179214722,609.6 -4.4681175556,53.2078808611,609.6 -4.4584117778,53.2147212778,609.6 + + + + + + EGRU302A CAERNARFON + <table border="1" cellpadding="1" cellspacing="0" row_id="7560" txt_name="CAERNARFON"><tr><td>A circle, 2 NM radius, centred at 530607N 0042015W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.3376138889,53.1351023087,609.6 -4.3433043386,53.1349257699,609.6 -4.3489343296,53.1343980293,609.6 -4.3544440496,53.1335246937,609.6 -4.3597749729,53.1323150412,609.6 -4.364870486,53.1307819219,609.6 -4.3696764915,53.1289416205,609.6 -4.3741419857,53.1268136824,609.6 -4.3782196013,53.1244207048,609.6 -4.3818661114,53.1217880954,609.6 -4.3850428872,53.1189438015,609.6 -4.3877163068,53.1159180117,609.6 -4.3898581093,53.1127428348,609.6 -4.3914456909,53.1094519572,609.6 -4.3924623404,53.1060802854,609.6 -4.3928974115,53.1026635745,609.6 -4.3927464296,53.0992380488,609.6 -4.3920111343,53.0958400175,609.6 -4.3906994541,53.09250549,609.6 -4.3888254173,53.0892697945,609.6 -4.3864089981,53.0861672042,609.6 -4.3834758997,53.0832305756,609.6 -4.3800572789,53.0804910008,609.6 -4.3761894124,53.0779774803,609.6 -4.3719133111,53.0757166167,609.6 -4.3672742846,53.0737323344,609.6 -4.3623214621,53.0720456282,609.6 -4.357107273,53.070674342,609.6 -4.3516868947,53.0696329815,609.6 -4.3461176715,53.0689325613,609.6 -4.3404585112,53.0685804894,609.6 -4.3347692666,53.0685804894,609.6 -4.3291101063,53.0689325613,609.6 -4.3235408831,53.0696329815,609.6 -4.3181205048,53.070674342,609.6 -4.3129063157,53.0720456282,609.6 -4.3079534931,53.0737323344,609.6 -4.3033144667,53.0757166167,609.6 -4.2990383653,53.0779774803,609.6 -4.2951704989,53.0804910008,609.6 -4.2917518781,53.0832305756,609.6 -4.2888187797,53.0861672042,609.6 -4.2864023605,53.0892697945,609.6 -4.2845283237,53.09250549,609.6 -4.2832166435,53.0958400175,609.6 -4.2824813481,53.0992380488,609.6 -4.2823303663,53.1026635745,609.6 -4.2827654374,53.1060802854,609.6 -4.2837820869,53.1094519572,609.6 -4.2853696685,53.1127428348,609.6 -4.2875114709,53.1159180117,609.6 -4.2901848905,53.1189438015,609.6 -4.2933616663,53.1217880954,609.6 -4.2970081764,53.1244207048,609.6 -4.3010857921,53.1268136824,609.6 -4.3055512863,53.1289416205,609.6 -4.3103572918,53.1307819219,609.6 -4.3154528048,53.1323150412,609.6 -4.3207837282,53.1335246937,609.6 -4.3262934482,53.1343980293,609.6 -4.3319234391,53.1349257699,609.6 -4.3376138889,53.1351023087,609.6 + + + + + + EGRU302B CAERNARFON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7743" txt_name="CAERNARFON RWY 07"><tr><td>530455N 0042437W -<br/>530525N 0042455W -<br/>530543N 0042331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to<br/>530512N 0042313W -<br/>530455N 0042437W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4103138889,53.081825,609.6 -4.3869033611,53.0867385278,609.6 -4.3889621559,53.0894737148,609.6 -4.3906033207,53.0923094586,609.6 -4.3918134167,53.0952226944,609.6 -4.4152138889,53.0903111111,609.6 -4.4103138889,53.081825,609.6 + + + + + + EGRU302C CAERNARFON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8078" txt_name="CAERNARFON RWY 25"><tr><td>530718N 0041554W -<br/>530648N 0041536W -<br/>530630N 0041700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to<br/>530701N 0041718W -<br/>530718N 0041554W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.2648611111,53.1217694444,609.6 -4.2882921389,53.1168824722,609.6 -4.286237965,53.114145571,609.6 -4.2846023923,53.1113083851,609.6 -4.2833986667,53.1083940278,609.6 -4.2599555556,53.1132833333,609.6 -4.2648611111,53.1217694444,609.6 + + + + + + EGRU303A WOODVALE + <table border="1" cellpadding="1" cellspacing="0" row_id="7986" txt_name="WOODVALE"><tr><td>A circle, 2 NM radius, centred at 533454N 0030327W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0575277778,53.615002394,609.6 -3.0632825546,53.6148258671,609.6 -3.0689761866,53.6142981621,609.6 -3.0745481834,53.6134248857,609.6 -3.0799393554,53.6122153156,609.6 -3.0850924473,53.6106823016,609.6 -3.0899527491,53.608842128,609.6 -3.0944686797,53.6067143394,609.6 -3.0985923365,53.6043215321,609.6 -3.1022800041,53.6016891128,609.6 -3.1054926184,53.5988450274,609.6 -3.108196179,53.5958194632,609.6 -3.1103621078,53.5926445269,609.6 -3.1119675482,53.5893539031,609.6 -3.1129956032,53.5859824958,609.6 -3.1134355093,53.5825660578,609.6 -3.1132827447,53.5791408106,609.6 -3.1125390718,53.5757430602,609.6 -3.1112125119,53.572408813,609.6 -3.1093172548,53.5691733937,609.6 -3.1068735025,53.5660710724,609.6 -3.1039072508,53.5631347019,609.6 -3.1004500096,53.5603953712,609.6 -3.0965384663,53.5578820774,609.6 -3.0922140949,53.5556214197,609.6 -3.0875227163,53.55363732,609.6 -3.0825140131,53.5519507702,609.6 -3.0772410052,53.5505796121,609.6 -3.0717594907,53.5495383493,609.6 -3.0661274586,53.5488379951,609.6 -3.0604044788,53.5484859565,609.6 -3.0546510767,53.5484859565,609.6 -3.048928097,53.5488379951,609.6 -3.0432960648,53.5495383493,609.6 -3.0378145503,53.5505796121,609.6 -3.0325415424,53.5519507702,609.6 -3.0275328393,53.55363732,609.6 -3.0228414607,53.5556214197,609.6 -3.0185170893,53.5578820774,609.6 -3.0146055459,53.5603953712,609.6 -3.0111483048,53.5631347019,609.6 -3.0081820531,53.5660710724,609.6 -3.0057383008,53.5691733937,609.6 -3.0038430436,53.572408813,609.6 -3.0025164838,53.5757430602,609.6 -3.0017728109,53.5791408106,609.6 -3.0016200463,53.5825660578,609.6 -3.0020599523,53.5859824958,609.6 -3.0030880073,53.5893539031,609.6 -3.0046934478,53.5926445269,609.6 -3.0068593766,53.5958194632,609.6 -3.0095629372,53.5988450274,609.6 -3.0127755514,53.6016891128,609.6 -3.0164632191,53.6043215321,609.6 -3.0205868758,53.6067143394,609.6 -3.0251028064,53.608842128,609.6 -3.0299631082,53.6106823016,609.6 -3.0351162002,53.6122153156,609.6 -3.0405073722,53.6134248857,609.6 -3.0460793689,53.6142981621,609.6 -3.051773001,53.6148258671,609.6 -3.0575277778,53.615002394,609.6 + + + + + + EGRU303B WOODVALE RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7742" txt_name="WOODVALE RWY 03"><tr><td>533204N 0030543W -<br/>533220N 0030630W -<br/>533320N 0030531W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to<br/>533304N 0030444W -<br/>533204N 0030543W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0953566667,53.5343348889,609.6 -3.0789983056,53.5509941389,609.6 -3.0835627936,53.5522709422,609.6 -3.0879157218,53.5537874214,609.6 -3.0920216944,53.55553125,609.6 -3.1083726944,53.5388743611,609.6 -3.0953566667,53.5343348889,609.6 + + + + + + EGRU303C WOODVALE RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7827" txt_name="WOODVALE RWY 21"><tr><td>533745N 0030111W -<br/>533728N 0030024W -<br/>533628N 0030123W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to<br/>533645N 0030210W -<br/>533745N 0030111W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0196293889,53.6290938333,609.6 -3.0360356111,53.6124486667,609.6 -3.031465676,53.6111705519,609.6 -3.0271083965,53.609652509,609.6 -3.0229993056,53.6079069167,609.6 -3.0065856389,53.6245544167,609.6 -3.0196293889,53.6290938333,609.6 + + + + + + EGRU303D WOODVALE RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7649" txt_name="WOODVALE RWY 08"><tr><td>533358N 0030816W -<br/>533430N 0030825W -<br/>533439N 0030647W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to<br/>533408N 0030633W -<br/>533358N 0030816W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1378758889,53.5660964167,609.6 -3.1091354444,53.5689110278,609.6 -3.1108744368,53.5717451964,609.6 -3.1121752414,53.5746614505,609.6 -3.1130270833,53.5776358333,609.6 -3.1403126389,53.5749635278,609.6 -3.1378758889,53.5660964167,609.6 + + + + + + EGRU303E WOODVALE RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8080" txt_name="WOODVALE RWY 26"><tr><td>533526N 0025847W -<br/>533454N 0025838W -<br/>533446N 0030006W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to<br/>533518N 0030010W -<br/>533526N 0025847W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9796778611,53.5906015833,609.6 -3.002726,53.58837175,609.6 -3.0019410534,53.5853908477,609.6 -3.0016131184,53.5823798936,609.6 -3.0017448056,53.5793636389,609.6 -2.9772401944,53.5817345,609.6 -2.9796778611,53.5906015833,609.6 + + + + + + EGRU304A BLACKPOOL + <table border="1" cellpadding="1" cellspacing="0" row_id="7934" txt_name="BLACKPOOL"><tr><td>A circle, 2.5 NM radius, centred at 534618N 0030143W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0286111111,53.813265525,609.6 -3.0350967314,53.813087897,609.6 -3.0415268553,53.8125565327,609.6 -3.0478464658,53.8116759789,609.6 -3.0540014992,53.8104537697,609.6 -3.0599393125,53.8089003614,609.6 -3.0656091358,53.807029043,609.6 -3.0709625102,53.8048558208,609.6 -3.0759537036,53.8023992809,609.6 -3.0805401032,53.7996804291,609.6 -3.0846825797,53.7967225097,609.6 -3.0883458215,53.7935508061,609.6 -3.0914986345,53.7901924229,609.6 -3.0941142068,53.7866760536,609.6 -3.0961703336,53.783031734,609.6 -3.0976496038,53.7792905852,609.6 -3.0985395433,53.7754845467,609.6 -3.0988327171,53.7716461032,609.6 -3.0985267866,53.7678080074,609.6 -3.0976245247,53.764003,609.6 -3.0961337862,53.7602635307,609.6 -3.0940674357,53.7566214818,609.6 -3.0914432325,53.753107897,609.6 -3.088283675,53.7497527174,609.6 -3.0846158053,53.7465845272,609.6 -3.0804709746,53.7436303116,609.6 -3.0758845751,53.7409152277,609.6 -3.0708957357,53.7384623916,609.6 -3.0655469893,53.7362926829,609.6 -3.0598839103,53.734424568,609.6 -3.0539547281,53.7328739443,609.6 -3.0478099183,53.7316540056,609.6 -3.0415017762,53.7307751313,609.6 -3.0350839746,53.7302447983,609.6 -3.0286111111,53.7300675179,609.6 -3.0221382476,53.7302447983,609.6 -3.015720446,53.7307751313,609.6 -3.0094123039,53.7316540056,609.6 -3.0032674941,53.7328739443,609.6 -2.9973383119,53.734424568,609.6 -2.9916752329,53.7362926829,609.6 -2.9863264865,53.7384623916,609.6 -2.9813376472,53.7409152277,609.6 -2.9767512476,53.7436303116,609.6 -2.972606417,53.7465845272,609.6 -2.9689385472,53.7497527174,609.6 -2.9657789898,53.753107897,609.6 -2.9631547866,53.7566214818,609.6 -2.961088436,53.7602635307,609.6 -2.9595976975,53.764003,609.6 -2.9586954356,53.7678080074,609.6 -2.9583895052,53.7716461032,609.6 -2.9586826789,53.7754845467,609.6 -2.9595726185,53.7792905852,609.6 -2.9610518886,53.783031734,609.6 -2.9631080155,53.7866760536,609.6 -2.9657235877,53.7901924229,609.6 -2.9688764007,53.7935508061,609.6 -2.9725396425,53.7967225097,609.6 -2.976682119,53.7996804291,609.6 -2.9812685186,53.8023992809,609.6 -2.986259712,53.8048558208,609.6 -2.9916130864,53.807029043,609.6 -2.9972829098,53.8089003614,609.6 -3.003220723,53.8104537697,609.6 -3.0093757564,53.8116759789,609.6 -3.0156953669,53.8125565327,609.6 -3.0221254908,53.813087897,609.6 -3.0286111111,53.813265525,609.6 + + + + + + EGRU304B BLACKPOOL RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="7600" txt_name="BLACKPOOL RWY 10"><tr><td>534617N 0030708W -<br/>534649N 0030704W -<br/>534646N 0030551W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to<br/>534613N 0030556W -<br/>534617N 0030708W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1188944444,53.7713694444,609.6 -3.0987998889,53.7704148056,609.6 -3.0987721547,53.7734150578,609.6 -3.0983793941,53.7764063199,609.6 -3.0976235833,53.7793730278,609.6 -3.1176611111,53.780325,609.6 -3.1188944444,53.7713694444,609.6 + + + + + + EGRU304C BLACKPOOL RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7637" txt_name="BLACKPOOL RWY 28"><tr><td>534618N 0025618W -<br/>534546N 0025622W -<br/>534549N 0025735W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to<br/>534622N 0025730W -<br/>534618N 0025618W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.93825,53.7716805556,609.6 -2.9584088889,53.7726654167,609.6 -2.9584724548,53.769665424,609.6 -2.9589008064,53.7666759456,609.6 -2.9596916389,53.7637125278,609.6 -2.9394777778,53.762725,609.6 -2.93825,53.7716805556,609.6 + + + + + + EGRU304D BLACKPOOL RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="7926" txt_name="BLACKPOOL RWY 13"><tr><td>534750N 0030625W -<br/>534816N 0030552W -<br/>534752N 0030459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to<br/>534725N 0030529W -<br/>534750N 0030625W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.106925,53.7973527778,609.6 -3.0913692778,53.7903458056,609.6 -3.0889268368,53.7929841056,609.6 -3.0861684105,53.7955109174,609.6 -3.0831083889,53.797913,609.6 -3.097725,53.8044972222,609.6 -3.106925,53.7973527778,609.6 + + + + + + EGRU304E BLACKPOOL RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="7807" txt_name="BLACKPOOL RWY 31"><tr><td>534444N 0025801W -<br/>534418N 0025834W -<br/>534427N 0025854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to<br/>534451N 0025817W -<br/>534444N 0025801W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9668805556,53.7454194444,609.6 -2.9714730833,53.74749825,609.6 -2.9745715778,53.7451145435,609.6 -2.9779523219,53.7428697567,609.6 -2.9815976111,53.7407756111,609.6 -2.9760666667,53.7382722222,609.6 -2.9668805556,53.7454194444,609.6 + + + + + + EGRU305A HAWARDEN + <table border="1" cellpadding="1" cellspacing="0" row_id="7625" txt_name="HAWARDEN"><tr><td>A circle, 2.5 NM radius, centred at 531041N 0025840W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9777777778,53.2196585709,609.6 -2.9841733813,53.2194809288,609.6 -2.9905142623,53.2189495226,609.6 -2.9967461703,53.218068899,609.6 -3.0028157954,53.2168465921,609.6 -3.0086712274,53.2152930587,609.6 -3.0142624035,53.2134215879,609.6 -3.0195415387,53.2112481864,609.6 -3.0244635363,53.2087914411,609.6 -3.0289863748,53.2060723582,609.6 -3.0330714673,53.2031141832,609.6 -3.0366839906,53.1999422005,609.6 -3.0397931814,53.1965835162,609.6 -3.0423725966,53.1930668254,609.6 -3.0444003364,53.1894221661,609.6 -3.0458592271,53.1856806614,609.6 -3.0467369634,53.1818742535,609.6 -3.0470262088,53.1780354301,609.6 -3.0467246526,53.1741969468,609.6 -3.0458350247,53.1703915479,609.6 -3.0443650667,53.1666516866,609.6 -3.0423274606,53.1630092492,609.6 -3.0397397161,53.1594952831,609.6 -3.0366240167,53.1561397334,609.6 -3.0330070272,53.1529711887,609.6 -3.0289196629,53.1500166378,609.6 -3.0243968244,53.1473012419,609.6 -3.0194770986,53.1448481206,609.6 -3.0142024296,53.1426781572,609.6 -3.0086177621,53.140809821,609.6 -3.0027706593,53.1392590123,609.6 -2.9967109005,53.1380389272,609.6 -2.9904900599,53.137159947,609.6 -2.9841610705,53.1366295498,609.6 -2.9777777778,53.1364522479,609.6 -2.971394485,53.1366295498,609.6 -2.9650654957,53.137159947,609.6 -2.958844655,53.1380389272,609.6 -2.9527848963,53.1392590123,609.6 -2.9469377935,53.140809821,609.6 -2.9413531259,53.1426781572,609.6 -2.936078457,53.1448481206,609.6 -2.9311587312,53.1473012419,609.6 -2.9266358927,53.1500166378,609.6 -2.9225485284,53.1529711887,609.6 -2.9189315388,53.1561397334,609.6 -2.9158158395,53.1594952831,609.6 -2.913228095,53.1630092492,609.6 -2.9111904889,53.1666516866,609.6 -2.9097205308,53.1703915479,609.6 -2.9088309029,53.1741969468,609.6 -2.9085293468,53.1780354301,609.6 -2.9088185922,53.1818742535,609.6 -2.9096963285,53.1856806614,609.6 -2.9111552191,53.1894221661,609.6 -2.9131829589,53.1930668254,609.6 -2.9157623742,53.1965835162,609.6 -2.918871565,53.1999422005,609.6 -2.9224840883,53.2031141832,609.6 -2.9265691808,53.2060723582,609.6 -2.9310920193,53.2087914411,609.6 -2.9360140169,53.2112481864,609.6 -2.941293152,53.2134215879,609.6 -2.9468843281,53.2152930587,609.6 -2.9527397602,53.2168465921,609.6 -2.9588093852,53.218068899,609.6 -2.9650412933,53.2189495226,609.6 -2.9713821742,53.2194809288,609.6 -2.9777777778,53.2196585709,609.6 + + + + + + EGRU305B HAWARDEN RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7589" txt_name="HAWARDEN RWY 04"><tr><td>530811N 0030141W -<br/>530832N 0030222W -<br/>530859N 0030143W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to<br/>530838N 0030102W -<br/>530811N 0030141W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.028075,53.136375,609.6 -3.0172443611,53.1438768889,609.6 -3.021239603,53.1456745645,609.6 -3.0250093088,53.1476405689,609.6 -3.0285338889,53.1497646944,609.6 -3.0393527778,53.1422694444,609.6 -3.028075,53.136375,609.6 + + + + + + EGRU305C HAWARDEN RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7923" txt_name="HAWARDEN RWY 22"><tr><td>531311N 0025538W -<br/>531250N 0025457W -<br/>531223N 0025537W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to<br/>531244N 0025618W -<br/>531311N 0025538W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9271138889,53.2198527778,609.6 -2.9382055556,53.2122030556,609.6 -2.9342095663,53.2104006477,609.6 -2.9304407113,53.2084299101,609.6 -2.9269186111,53.2063011111,609.6 -2.9158138889,53.2139583333,609.6 -2.9271138889,53.2198527778,609.6 + + + + + + EGRU306A WARTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7831" txt_name="WARTON"><tr><td>A circle, 2.5 NM radius, centred at 534442N 0025300W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8834361111,53.7866240444,609.6 -2.889917622,53.7864464157,609.6 -2.8963436718,53.7859150496,609.6 -2.9026592785,53.7850344927,609.6 -2.9088104129,53.783812279,609.6 -2.9147444653,53.7822588652,609.6 -2.9204106983,53.78038754,609.6 -2.9257606835,53.7782143098,609.6 -2.9307487181,53.7757577607,609.6 -2.935332216,53.7730388986,609.6 -2.9394720729,53.7700809678,609.6 -2.9431329994,53.7669092518,609.6 -2.946283821,53.7635508551,609.6 -2.9488977427,53.7600344714,609.6 -2.9509525737,53.7563901367,609.6 -2.9524309136,53.752648972,609.6 -2.9533202961,53.7488429169,609.6 -2.9536132906,53.7450044565,609.6 -2.9533075598,53.7411663433,609.6 -2.9524058748,53.7373613184,609.6 -2.950916085,53.7336218315,609.6 -2.9488510467,53.7299797653,609.6 -2.9462285079,53.7264661634,609.6 -2.9430709527,53.7231109672,609.6 -2.9394054057,53.7199427611,609.6 -2.9352631985,53.7169885305,609.6 -2.9306797005,53.7142734326,609.6 -2.9256940162,53.7118205837,609.6 -2.9203486515,53.7096508635,609.6 -2.9146891521,53.7077827387,609.6 -2.9087637168,53.7062321067,609.6 -2.9026227897,53.7050121615,609.6 -2.896318633,53.7041332824,609.6 -2.8899048857,53.7036029465,609.6 -2.8834361111,53.7034256651,609.6 -2.8769673366,53.7036029465,609.6 -2.8705535893,53.7041332824,609.6 -2.8642494325,53.7050121615,609.6 -2.8581085054,53.7062321067,609.6 -2.8521830701,53.7077827387,609.6 -2.8465235707,53.7096508635,609.6 -2.841178206,53.7118205837,609.6 -2.8361925217,53.7142734326,609.6 -2.8316090238,53.7169885305,609.6 -2.8274668166,53.7199427611,609.6 -2.8238012695,53.7231109672,609.6 -2.8206437143,53.7264661634,609.6 -2.8180211755,53.7299797653,609.6 -2.8159561372,53.7336218315,609.6 -2.8144663475,53.7373613184,609.6 -2.8135646624,53.7411663433,609.6 -2.8132589317,53.7450044565,609.6 -2.8135519261,53.7488429169,609.6 -2.8144413086,53.752648972,609.6 -2.8159196485,53.7563901367,609.6 -2.8179744795,53.7600344714,609.6 -2.8205884012,53.7635508551,609.6 -2.8237392229,53.7669092518,609.6 -2.8274001493,53.7700809678,609.6 -2.8315400062,53.7730388986,609.6 -2.8361235041,53.7757577607,609.6 -2.8411115387,53.7782143098,609.6 -2.846461524,53.78038754,609.6 -2.8521277569,53.7822588652,609.6 -2.8580618093,53.783812279,609.6 -2.8642129437,53.7850344927,609.6 -2.8705285504,53.7859150496,609.6 -2.8769546003,53.7864464157,609.6 -2.8834361111,53.7866240444,609.6 + + + + + + EGRU306B WARTON RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7573" txt_name="WARTON RWY 07"><tr><td>534322N 0025811W -<br/>534353N 0025828W -<br/>534409N 0025707W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to<br/>534339N 0025649W -<br/>534322N 0025811W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9695861111,53.7228194444,609.6 -2.9469941389,53.72740525,609.6 -2.9489722681,53.730166133,609.6 -2.9506099817,53.7330043435,609.6 -2.9518986944,53.7359051389,609.6 -2.974475,53.7313222222,609.6 -2.9695861111,53.7228194444,609.6 + + + + + + EGRU306C WARTON RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7519" txt_name="WARTON RWY 25"><tr><td>534602N 0024750W -<br/>534531N 0024732W -<br/>534515N 0024854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to<br/>534545N 0024911W -<br/>534602N 0024750W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7972166667,53.7671638889,609.6 -2.8198246111,53.7626105556,609.6 -2.8178532713,53.7598472272,609.6 -2.8162233905,53.7570068727,609.6 -2.8149433889,53.7541042778,609.6 -2.7923166667,53.7586611111,609.6 -2.7972166667,53.7671638889,609.6 + + + + + + EGRU307A LIVERPOOL + <table border="1" cellpadding="1" cellspacing="0" row_id="7710" txt_name="LIVERPOOL"><tr><td>A circle, 2.5 NM radius, centred at 532001N 0025059W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8497222222,53.3752130345,609.6 -2.8561411049,53.3750353962,609.6 -2.862505065,53.3745040011,609.6 -2.8687596537,53.3736233958,609.6 -2.8748513663,53.3724011146,609.6 -2.8807281029,53.3708476142,609.6 -2.8863396181,53.3689761835,609.6 -2.8916379523,53.3668028293,609.6 -2.8965778448,53.364346138,609.6 -2.901117121,53.361627116,609.6 -2.9052170537,53.3586690083,609.6 -2.9088426935,53.355497099,609.6 -2.9119631657,53.3521384939,609.6 -2.9145519318,53.3486218877,609.6 -2.916587013,53.3449773177,609.6 -2.9180511743,53.3412359065,609.6 -2.9189320668,53.3374295957,609.6 -2.9192223284,53.333590872,609.6 -2.9189196412,53.3297524905,609.6 -2.9180267463,53.3259471944,609.6 -2.9165514144,53.322207436,609.6 -2.9145063748,53.3185651006,609.6 -2.9119092018,53.3150512345,609.6 -2.9087821604,53.311695782,609.6 -2.9051520127,53.3085273302,609.6 -2.9010497869,53.3055728673,609.6 -2.8965105107,53.3028575532,609.6 -2.8915729112,53.3004045067,609.6 -2.8862790848,53.29823461,609.6 -2.880674139,53.2963663318,609.6 -2.8748058092,53.2948155716,609.6 -2.868724055,53.2935955249,609.6 -2.8624806369,53.2927165725,609.6 -2.8561286793,53.2921861921,609.6 -2.8497222222,53.2920088958,609.6 -2.8433157651,53.2921861921,609.6 -2.8369638075,53.2927165725,609.6 -2.8307203894,53.2935955249,609.6 -2.8246386352,53.2948155716,609.6 -2.8187703055,53.2963663318,609.6 -2.8131653596,53.29823461,609.6 -2.8078715332,53.3004045067,609.6 -2.8029339337,53.3028575532,609.6 -2.7983946575,53.3055728673,609.6 -2.7942924318,53.3085273302,609.6 -2.7906622841,53.311695782,609.6 -2.7875352426,53.3150512345,609.6 -2.7849380696,53.3185651006,609.6 -2.78289303,53.322207436,609.6 -2.7814176981,53.3259471944,609.6 -2.7805248032,53.3297524905,609.6 -2.7802221161,53.333590872,609.6 -2.7805123776,53.3374295957,609.6 -2.7813932701,53.3412359065,609.6 -2.7828574314,53.3449773177,609.6 -2.7848925127,53.3486218877,609.6 -2.7874812787,53.3521384939,609.6 -2.7906017509,53.355497099,609.6 -2.7942273907,53.3586690083,609.6 -2.7983273235,53.361627116,609.6 -2.8028665997,53.364346138,609.6 -2.8078064921,53.3668028293,609.6 -2.8131048264,53.3689761835,609.6 -2.8187163415,53.3708476142,609.6 -2.8245930782,53.3724011146,609.6 -2.8306847907,53.3736233958,609.6 -2.8369393794,53.3745040011,609.6 -2.8433033395,53.3750353962,609.6 -2.8497222222,53.3752130345,609.6 + + + + + + EGRU307B LIVERPOOL RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7648" txt_name="LIVERPOOL RWY 09"><tr><td>531930N 0025625W -<br/>532002N 0025629W -<br/>532006N 0025509W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to<br/>531933N 0025505W -<br/>531930N 0025625W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9402555556,53.3249333333,609.6 -2.9180339167,53.3259700278,609.6 -2.9187785016,53.3289367765,609.6 -2.9191640932,53.3319279325,609.6 -2.9191886111,53.3349279444,609.6 -2.9414,53.3338916667,609.6 -2.9402555556,53.3249333333,609.6 + + + + + + EGRU307C LIVERPOOL RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7772" txt_name="LIVERPOOL RWY 27"><tr><td>532032N 0024530W -<br/>532000N 0024526W -<br/>531956N 0024649W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to<br/>532029N 0024653W -<br/>532032N 0024530W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7584444444,53.3423027778,609.6 -2.7814016667,53.3412629167,609.6 -2.7806603436,53.3382957709,609.6 -2.7802782982,53.3353043619,609.6 -2.7802574444,53.33230425,609.6 -2.7572916667,53.3333444444,609.6 -2.7584444444,53.3423027778,609.6 + + + + + + EGRU308A MANCHESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="7712" txt_name="MANCHESTER"><tr><td>A circle, 2.5 NM radius, centred at 532113N 0021630W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2749509722,53.3953507267,609.6 -2.2813728845,53.3951730888,609.6 -2.2877398481,53.3946416951,609.6 -2.2939973885,53.3937610922,609.6 -2.3000919755,53.3925388144,609.6 -2.3059714848,53.3909853182,609.6 -2.3115856468,53.3891138927,609.6 -2.3168864796,53.3869405445,609.6 -2.3218287009,53.3844838603,609.6 -2.3263701163,53.3817648461,609.6 -2.3304719804,53.3788067471,609.6 -2.3340993272,53.3756348473,609.6 -2.3372212675,53.3722762524,609.6 -2.3398112505,53.3687596571,609.6 -2.3418472871,53.3651150987,609.6 -2.3433121343,53.3613736996,609.6 -2.3441934376,53.3575674013,609.6 -2.3444838314,53.3537286906,609.6 -2.344180997,53.3498903223,609.6 -2.3432876769,53.3460850394,609.6 -2.3418116456,53.3423452944,609.6 -2.3397656387,53.3387029721,609.6 -2.3371672386,53.335189119,609.6 -2.3340387211,53.331833679,609.6 -2.330406861,53.3286652393,609.6 -2.3263027012,53.3257107877,609.6 -2.3217612858,53.3229954842,609.6 -2.3168213602,53.3205424474,609.6 -2.3115250407,53.3183725594,609.6 -2.3059174558,53.3165042887,609.6 -2.3000463636,53.3149535347,609.6 -2.2939617469,53.3137334931,609.6 -2.2877153906,53.3128545442,609.6 -2.2813604439,53.312324166,609.6 -2.2749509722,53.3121468705,609.6 -2.2685415005,53.312324166,609.6 -2.2621865539,53.3128545442,609.6 -2.2559401975,53.3137334931,609.6 -2.2498555809,53.3149535347,609.6 -2.2439844887,53.3165042887,609.6 -2.2383769038,53.3183725594,609.6 -2.2330805842,53.3205424474,609.6 -2.2281406587,53.3229954842,609.6 -2.2235992433,53.3257107877,609.6 -2.2194950835,53.3286652393,609.6 -2.2158632233,53.331833679,609.6 -2.2127347058,53.335189119,609.6 -2.2101363058,53.3387029721,609.6 -2.2080902988,53.3423452944,609.6 -2.2066142676,53.3460850394,609.6 -2.2057209474,53.3498903223,609.6 -2.2054181131,53.3537286906,609.6 -2.2057085069,53.3575674013,609.6 -2.2065898101,53.3613736996,609.6 -2.2080546573,53.3651150987,609.6 -2.210090694,53.3687596571,609.6 -2.2126806769,53.3722762524,609.6 -2.2158026173,53.3756348473,609.6 -2.2194299641,53.3788067471,609.6 -2.2235318281,53.3817648461,609.6 -2.2280732435,53.3844838603,609.6 -2.2330154648,53.3869405445,609.6 -2.2383162976,53.3891138927,609.6 -2.2439304597,53.3909853182,609.6 -2.2498099689,53.3925388144,609.6 -2.255904556,53.3937610922,609.6 -2.2621620964,53.3946416951,609.6 -2.2685290599,53.3951730888,609.6 -2.2749509722,53.3953507267,609.6 + + + + + + EGRU308B MANCHESTER RWY 05L + <table border="1" cellpadding="1" cellspacing="0" row_id="7992" txt_name="MANCHESTER RWY 05L"><tr><td>531857N 0022029W -<br/>531922N 0022103W -<br/>531953N 0022000W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to<br/>531928N 0021926W -<br/>531857N 0022029W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3414111111,53.3158111111,609.6 -2.3238734167,53.324307,609.6 -2.3273308396,53.3264781521,609.6 -2.3304832641,53.3288109833,609.6 -2.3333465833,53.3312738611,609.6 -2.3508361111,53.3228,609.6 -2.3414111111,53.3158111111,609.6 + + + + + + EGRU308C MANCHESTER RWY 23R + <table border="1" cellpadding="1" cellspacing="0" row_id="7720" txt_name="MANCHESTER RWY 23R"><tr><td>532335N 0021220W -<br/>532310N 0021146W -<br/>532235N 0021259W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to<br/>532300N 0021333W -<br/>532335N 0021220W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2055305556,53.3930222222,609.6 -2.2257580556,53.3832712778,609.6 -2.2223686207,53.3810587658,609.6 -2.2192198687,53.3787240926,609.6 -2.2163605833,53.3762599167,609.6 -2.1960833333,53.3860333333,609.6 -2.2055305556,53.3930222222,609.6 + + + + + + EGRU308D MANCHESTER RWY 05R + <table border="1" cellpadding="1" cellspacing="0" row_id="7646" txt_name="MANCHESTER RWY 05R"><tr><td>531801N 0022151W -<br/>531826N 0022225W -<br/>531942N 0021948W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to<br/>531919N 0021910W -<br/>531801N 0022151W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3642722222,53.3002166667,609.6 -2.3194853889,53.3219233611,609.6 -2.3232527059,53.3239194034,609.6 -2.326738245,53.3260924911,609.6 -2.3299518889,53.3284110278,609.6 -2.3736972222,53.3072055556,609.6 -2.3642722222,53.3002166667,609.6 + + + + + + EGRU309A MANCHESTER BARTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7517" txt_name="MANCHESTER BARTON"><tr><td>532618N 0022327W thence clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532749N 0022008W -<br/>532638N 0022258W -<br/>532618N 0022327W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3907305556,53.4382972222,609.6 -2.3827777778,53.4438888889,609.6 -2.3355777778,53.4635694444,609.6 -2.3343558953,53.4669212271,609.6 -2.3338295699,53.4703398171,609.6 -2.3338945616,53.473772581,609.6 -2.3345503253,53.4771831975,609.6 -2.3357900617,53.4805355709,609.6 -2.3376007831,53.4837942136,609.6 -2.3399634458,53.4869246223,609.6 -2.3428531463,53.4898936441,609.6 -2.3462393808,53.4926698285,609.6 -2.3500863655,53.4952237618,609.6 -2.3543534126,53.49752838,609.6 -2.3589953605,53.4995592571,609.6 -2.3639630523,53.5012948649,609.6 -2.3692038574,53.502716803,609.6 -2.3746622316,53.5038099946,609.6 -2.3802803087,53.5045628477,609.6 -2.3859985173,53.5049673785,609.6 -2.391756217,53.5050192971,609.6 -2.3974923454,53.5047180527,609.6 -2.4031460708,53.5040668403,609.6 -2.4086574411,53.5030725655,609.6 -2.4139680243,53.5017457719,609.6 -2.4190215316,53.5001005278,609.6 -2.4237644171,53.4981542763,609.6 -2.4281464477,53.4959276492,609.6 -2.4321212367,53.4934442471,609.6 -2.4356467354,53.490730388,609.6 -2.4386856781,53.4878148267,609.6 -2.4412059746,53.4847284494,609.6 -2.4431810468,53.4815039446,609.6 -2.4445901066,53.4781754567,609.6 -2.4454183711,53.4747782227,609.6 -2.4456572136,53.4713481991,609.6 -2.4453042492,53.4679216808,609.6 -2.4443633537,53.464534917,609.6 -2.4428446174,53.4612237276,609.6 -2.4407642317,53.4580231253,609.6 -2.4381443133,53.4549669457,609.6 -2.4350126656,53.4520874903,609.6 -2.4314024809,53.4494151868,609.6 -2.4273519867,53.4469782683,609.6 -2.4229040406,53.4448024765,609.6 -2.4181056758,53.442910791,609.6 -2.4130076057,53.4413231879,609.6 -2.407663689,53.4400564305,609.6 -2.4021303634,53.4391238927,609.6 -2.3964660531,53.4385354193,609.6 -2.3907305556,53.4382972222,609.6 + + + + + + EGRU309B MANCHESTER BARTON RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="7691" txt_name="MANCHESTER BARTON RWY 02"><tr><td>532531N 0022405W -<br/>532540N 0022457W -<br/>532626N 0022437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532619N 0022344W -<br/>532531N 0022405W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.401275,53.4254111111,609.6 -2.395574,53.4384753889,609.6 -2.4005470392,53.4389250988,609.6 -2.4054320863,53.43964046,609.6 -2.4101894444,53.4406156667,609.6 -2.4158305556,53.4276777778,609.6 -2.401275,53.4254111111,609.6 + + + + + + EGRU309C MANCHESTER BARTON RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7868" txt_name="MANCHESTER BARTON RWY 20"><tr><td>533107N 0022234W -<br/>533059N 0022141W -<br/>533008N 0022204W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>533016N 0022256W -<br/>533107N 0022234W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3760861111,53.5186583333,609.6 -2.3822588889,53.5045544444,609.6 -2.3773016223,53.5040188623,609.6 -2.3724457077,53.5032188044,609.6 -2.3677307778,53.5021608056,609.6 -2.3614972222,53.5163916667,609.6 -2.3760861111,53.5186583333,609.6 + + + + + + EGRU309D MANCHESTER BARTON RWY 08L + <table border="1" cellpadding="1" cellspacing="0" row_id="8152" txt_name="MANCHESTER BARTON RWY 08L"><tr><td>532741N 0022809W -<br/>532813N 0022816W -<br/>532820N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532748N 0022637W -<br/>532741N 0022809W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.469125,53.4613111111,609.6 -2.4437155833,53.4632409444,609.6 -2.4447561923,53.466179194,609.6 -2.4453488031,53.469161453,609.6 -2.4454885,53.4721634444,609.6 -2.4710111111,53.470225,609.6 -2.469125,53.4613111111,609.6 + + + + + + EGRU309E MANCHESTER BARTON RWY 26R + <table border="1" cellpadding="1" cellspacing="0" row_id="7901" txt_name="MANCHESTER BARTON RWY 26R"><tr><td>532856N 0021843W -<br/>532824N 0021836W -<br/>532817N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532850N 0022009W -<br/>532856N 0021843W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.312025,53.4822083333,609.6 -2.3359380833,53.4804198611,609.6 -2.3348219146,53.4774914143,609.6 -2.334152951,53.4745148593,609.6 -2.3339365278,53.4715144444,609.6 -2.3101361111,53.4732944444,609.6 -2.312025,53.4822083333,609.6 + + + + + + EGRU309F MANCHESTER BARTON RWY 08R + <table border="1" cellpadding="1" cellspacing="0" row_id="7954" txt_name="MANCHESTER BARTON RWY 08R"><tr><td>532740N 0022805W -<br/>532812N 0022812W -<br/>532819N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532747N 0022637W -<br/>532740N 0022805W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4681555556,53.4611444444,609.6 -2.4436079722,53.4629968056,609.6 -2.4446857783,53.4659298221,609.6 -2.4453162818,53.4689088672,609.6 -2.4454942778,53.4719096944,609.6 -2.4700277778,53.4700583333,609.6 -2.4681555556,53.4611444444,609.6 + + + + + + EGRU309G MANCHESTER BARTON RWY 26L + <table border="1" cellpadding="1" cellspacing="0" row_id="7672" txt_name="MANCHESTER BARTON RWY 26L"><tr><td>532855N 0021841W -<br/>532823N 0021834W -<br/>532816N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532848N 0022009W -<br/>532855N 0021841W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3112611111,53.4819472222,609.6 -2.3358037778,53.4801236111,609.6 -2.3347330633,53.4771895373,609.6 -2.3341101379,53.4742098286,609.6 -2.3339399722,53.47120875,609.6 -2.3093833333,53.4730333333,609.6 -2.3112611111,53.4819472222,609.6 + + + + + + EGRU309H MANCHESTER BARTON RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="8086" txt_name="MANCHESTER BARTON RWY 14"><tr><td>533006N 0022654W -<br/>533029N 0022616W -<br/>532956N 0022518W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to<br/>532934N 0022558W -<br/>533006N 0022654W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4483,53.5017388889,609.6 -2.4327602222,53.4927476389,609.6 -2.4293792212,53.4949799004,609.6 -2.4256737115,53.4970209071,609.6 -2.4216739444,53.4988539444,609.6 -2.4377944444,53.5081833333,609.6 -2.4483,53.5017388889,609.6 + + + + + + EGRU309I MANCHESTER BARTON RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="7860" txt_name="MANCHESTER BARTON RWY 32"><tr><td>532635N 0021932W -<br/>532612N 0022010W -<br/>532708N 0022146W -<br/>532727N 0022101W -<br/>532635N 0021932W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3255083333,53.4430694444,609.6 -2.3502631944,53.4574508611,609.6 -2.3628273056,53.4522123889,609.6 -2.3359944444,53.4366277778,609.6 -2.3255083333,53.4430694444,609.6 + + + + + + EGRU310A LEEDS BRADFORD + <table border="1" cellpadding="1" cellspacing="0" row_id="7998" txt_name="LEEDS BRADFORD"><tr><td>A circle, 2.5 NM radius, centred at 535158N 0013939W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6607694444,53.9076232001,609.6 -1.6672696727,53.9074455742,609.6 -1.6737142792,53.9069142166,609.6 -1.680048122,53.9060336738,609.6 -1.6862170157,53.9048114799,609.6 -1.6921681977,53.9032580914,609.6 -1.6978507839,53.9013867969,609.6 -1.7032162058,53.899213603,609.6 -1.7082186283,53.8967570955,609.6 -1.7128153425,53.8940382802,609.6 -1.7169671311,53.8910804012,609.6 -1.7206386033,53.8879087416,609.6 -1.7237984952,53.884550406,609.6 -1.7264199347,53.8810340875,609.6 -1.728480668,53.8773898217,609.6 -1.7299632451,53.8736487292,609.6 -1.7308551647,53.8698427491,609.6 -1.7311489757,53.8660043658,609.6 -1.7308423351,53.8621663314,609.6 -1.7299380227,53.858361386,609.6 -1.7284439118,53.8546219788,609.6 -1.7263728964,53.8509799916,609.6 -1.7237427766,53.8474664672,609.6 -1.7205761018,53.8441113463,609.6 -1.7168999752,53.8409432124,609.6 -1.712745819,53.83798905,609.6 -1.7081491048,53.8352740157,609.6 -1.7031490498,53.8328212248,609.6 -1.6977882823,53.8306515566,609.6 -1.692112479,53.8287834768,609.6 -1.6861699773,53.8272328825,609.6 -1.6800113658,53.8260129671,609.6 -1.6736890567,53.8251341097,609.6 -1.6672568431,53.8246037868,609.6 -1.6607694444,53.8244265098,609.6 -1.6542820458,53.8246037868,609.6 -1.6478498321,53.8251341097,609.6 -1.6415275231,53.8260129671,609.6 -1.6353689116,53.8272328825,609.6 -1.6294264099,53.8287834768,609.6 -1.6237506065,53.8306515566,609.6 -1.6183898391,53.8328212248,609.6 -1.6133897841,53.8352740157,609.6 -1.6087930699,53.83798905,609.6 -1.6046389137,53.8409432124,609.6 -1.6009627871,53.8441113463,609.6 -1.5977961123,53.8474664672,609.6 -1.5951659925,53.8509799916,609.6 -1.5930949771,53.8546219788,609.6 -1.5916008662,53.858361386,609.6 -1.5906965538,53.8621663314,609.6 -1.5903899132,53.8660043658,609.6 -1.5906837242,53.8698427491,609.6 -1.5915756438,53.8736487292,609.6 -1.5930582209,53.8773898217,609.6 -1.5951189542,53.8810340875,609.6 -1.5977403937,53.884550406,609.6 -1.6009002856,53.8879087416,609.6 -1.6045717577,53.8910804012,609.6 -1.6087235464,53.8940382802,609.6 -1.6133202606,53.8967570955,609.6 -1.618322683,53.899213603,609.6 -1.623688105,53.9013867969,609.6 -1.6293706912,53.9032580914,609.6 -1.6353218732,53.9048114799,609.6 -1.6414907669,53.9060336738,609.6 -1.6478246097,53.9069142166,609.6 -1.6542692162,53.9074455742,609.6 -1.6607694444,53.9076232001,609.6 + + + + + + EGRU310B LEEDS BRADFORD RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="8131" txt_name="LEEDS BRADFORD RWY 14"><tr><td>535406N 0014333W -<br/>535428N 0014253W -<br/>535359N 0014208W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to<br/>535337N 0014249W -<br/>535406N 0014333W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7258722222,53.9016444444,609.6 -1.7134789444,53.8936015278,609.6 -1.7099776463,53.8957754389,609.6 -1.7062197951,53.8977945137,609.6 -1.7022249444,53.8996482222,609.6 -1.7146083333,53.9076861111,609.6 -1.7258722222,53.9016444444,609.6 + + + + + + EGRU310C LEEDS BRADFORD RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="7645" txt_name="LEEDS BRADFORD RWY 32"><tr><td>534948N 0013543W -<br/>534927N 0013624W -<br/>534957N 0013710W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to<br/>535018N 0013629W -<br/>534948N 0013543W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5953916667,53.8301222222,609.6 -1.6081265,53.8384270556,609.6 -1.6116280666,53.8362559837,609.6 -1.6153847414,53.834239724,609.6 -1.619377,53.83238875,609.6 -1.6066305556,53.8240777778,609.6 -1.5953916667,53.8301222222,609.6 + + + + + + EGRU311A SHERBURN-IN-ELMET + <table border="1" cellpadding="1" cellspacing="0" row_id="7722" txt_name="SHERBURN-IN-ELMET"><tr><td>534837N 0011510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534823N 0011032W -<br/>534837N 0011510W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2527638889,53.8102666667,609.6 -1.2571224026,53.8079780693,609.6 -1.2610571872,53.8054348301,609.6 -1.2645260612,53.8026642646,609.6 -1.2674918691,53.7996961247,609.6 -1.2699228782,53.7965622774,609.6 -1.2717931161,53.7932963613,609.6 -1.2730826444,53.789933425,609.6 -1.2737777682,53.7865095498,609.6 -1.2738711768,53.7830614618,609.6 -1.2733620161,53.779626138,609.6 -1.2722558913,53.7762404097,609.6 -1.2705648008,53.7729405674,609.6 -1.2683070016,53.7697619731,609.6 -1.2655068083,53.7667386813,609.6 -1.2621943278,53.7639030758,609.6 -1.2584051335,53.7612855237,609.6 -1.2541798811,53.7589140514,609.6 -1.2495638721,53.7568140463,609.6 -1.2446065683,53.7550079858,609.6 -1.2393610627,53.7535151986,609.6 -1.2338835135,53.7523516589,609.6 -1.2282325455,53.7515298163,609.6 -1.2224686263,53.7510584638,609.6 -1.2166534236,53.7509426443,609.6 -1.2108491499,53.7511835969,609.6 -1.2051179016,53.7517787436,609.6 -1.1995209993,53.7527217173,609.6 -1.1941183362,53.7540024286,609.6 -1.1889677411,53.7556071738,609.6 -1.1841243629,53.75751878,609.6 -1.1796400828,53.759716788,609.6 -1.1755629604,53.7621776702,609.6 -1.1719367193,53.7648750804,609.6 -1.1688002784,53.7677801353,609.6 -1.1661873332,53.7708617218,609.6 -1.1641259915,53.7740868293,609.6 -1.1626384686,53.7774209021,609.6 -1.1617408441,53.7808282085,609.6 -1.1614428842,53.7842722237,609.6 -1.1617479309,53.78771602,609.6 -1.1626528599,53.7911226633,609.6 -1.1641481077,53.7944556092,609.6 -1.1662177682,53.7976790953,609.6 -1.168839758,53.8007585255,609.6 -1.1719860481,53.8036608427,609.6 -1.1756111111,53.8063611111,609.6 -1.2527638889,53.8102666667,609.6 + + + + + + EGRU311B SHERBURN-IN-ELMET RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="7852" txt_name="SHERBURN-IN-ELMET RWY 01"><tr><td>534422N 0011301W -<br/>534426N 0011355W -<br/>534506N 0011346W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534504N 0011251W -<br/>534422N 0011301W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.21695,53.7393833333,609.6 -1.2141693611,53.7510245278,609.6 -1.219247129,53.7509727092,609.6 -1.2243120647,53.7511927928,609.6 -1.2293228333,53.751683,609.6 -1.2319555556,53.7406444444,609.6 -1.21695,53.7393833333,609.6 + + + + + + EGRU311C SHERBURN-IN-ELMET RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="7612" txt_name="SHERBURN-IN-ELMET RWY 19"><tr><td>535003N 0011234W -<br/>534959N 0011140W -<br/>534827N 0011202W -<br/>534830N 0011257W -<br/>535003N 0011234W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2095805556,53.8342722222,609.6 -1.2157734444,53.8084004444,609.6 -1.2006255278,53.8076328889,609.6 -1.1945416667,53.8330111111,609.6 -1.2095805556,53.8342722222,609.6 + + + + + + EGRU311D SHERBURN-IN-ELMET RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7781" txt_name="SHERBURN-IN-ELMET RWY 06"><tr><td>534533N 0011659W -<br/>534601N 0011727W -<br/>534627N 0011616W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534558N 0011553W -<br/>534533N 0011659W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2829833333,53.7592861111,609.6 -1.2646393333,53.76597425,609.6 -1.267242897,53.7685715594,609.6 -1.2694385055,53.771297993,609.6 -1.271208,53.7741311111,609.6 -1.2909194444,53.7669444444,609.6 -1.2829833333,53.7592861111,609.6 + + + + + + EGRU311E SHERBURN-IN-ELMET RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7775" txt_name="SHERBURN-IN-ELMET RWY 24"><tr><td>534901N 0010912W -<br/>534834N 0010843W -<br/>534803N 0011008W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534823N 0011032W -<br/>534824N 0011054W -<br/>534901N 0010912W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1532638889,53.8170138889,609.6 -1.1817541111,53.8066739167,609.6 -1.1756111111,53.8063611111,609.6 -1.1720433532,53.8036694701,609.6 -1.1689177222,53.8007938611,609.6 -1.1453166667,53.8093583333,609.6 -1.1532638889,53.8170138889,609.6 + + + + + + EGRU311F SHERBURN-IN-ELMET RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="8062" txt_name="SHERBURN-IN-ELMET RWY 10"><tr><td>534728N 0011758W -<br/>534759N 0011745W -<br/>534746N 0011612W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534715N 0011625W -<br/>534728N 0011758W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2993888889,53.7910472222,609.6 -1.2736092222,53.7874488056,609.6 -1.2728948949,53.7904214951,609.6 -1.2717308379,53.7933439481,609.6 -1.2701264444,53.7961923611,609.6 -1.2958916667,53.7997888889,609.6 -1.2993888889,53.7910472222,609.6 + + + + + + EGRU311G SHERBURN-IN-ELMET RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="8141" txt_name="SHERBURN-IN-ELMET RWY 28"><tr><td>534640N 0010821W -<br/>534609N 0010834W -<br/>534620N 0010955W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534652N 0010942W -<br/>534640N 0010821W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1391666667,53.7778166667,609.6 -1.1617503611,53.7809968611,609.6 -1.1624732323,53.7780250319,609.6 -1.1636452747,53.7751038792,609.6 -1.1652568333,53.7722571667,609.6 -1.1426583333,53.769075,609.6 -1.1391666667,53.7778166667,609.6 + + + + + + EGRU311H SHERBURN-IN-ELMET RWY 10G + <table border="1" cellpadding="1" cellspacing="0" row_id="7635" txt_name="SHERBURN-IN-ELMET RWY 10G"><tr><td>534730N 0011755W -<br/>534801N 0011743W -<br/>534748N 0011611W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534717N 0011625W -<br/>534730N 0011755W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2986611111,53.7915666667,609.6 -1.2734953889,53.7880835278,609.6 -1.2726844522,53.7910487701,609.6 -1.2714251173,53.7939586218,609.6 -1.2697275556,53.7967893611,609.6 -1.2951916667,53.8003138889,609.6 -1.2986611111,53.7915666667,609.6 + + + + + + EGRU311I SHERBURN-IN-ELMET RWY 28G + <table border="1" cellpadding="1" cellspacing="0" row_id="8051" txt_name="SHERBURN-IN-ELMET RWY 28G"><tr><td>534643N 0010818W -<br/>534611N 0010830W -<br/>534623N 0010953W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534654N 0010942W -<br/>534643N 0010818W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1383,53.7785027778,609.6 -1.1616384444,53.7817617222,609.6 -1.1622457931,53.7787795064,609.6 -1.1633045603,53.7758418658,609.6 -1.1648060278,53.7729727222,609.6 -1.1417666667,53.7697555556,609.6 -1.1383,53.7785027778,609.6 + + + + + + EGRU312A NETHERTHORPE + <table border="1" cellpadding="1" cellspacing="0" row_id="7688" txt_name="NETHERTHORPE"><tr><td>A circle, 2 NM radius, centred at 531901N 0011146W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1962027778,53.350214989,609.6 -1.2019218329,53.3500384556,609.6 -1.2075801243,53.349510731,609.6 -1.2131175379,53.348637422,609.6 -1.2184752531,53.3474278065,609.6 -1.2235963708,53.3458947345,609.6 -1.2284265212,53.3440544906,609.6 -1.2329144439,53.3419266197,609.6 -1.2370125336,53.3395337186,609.6 -1.240677346,53.3369011946,609.6 -1.2438700589,53.3340569944,609.6 -1.246556882,53.3310313059,609.6 -1.2487094133,53.327856237,609.6 -1.2503049366,53.3245654734,609.6 -1.2513266582,53.3211939204,609.6 -1.2517638795,53.317777332,609.6 -1.251612105,53.3143519312,609.6 -1.2508730844,53.3109540261,609.6 -1.2495547875,53.3076196243,609.6 -1.2476713144,53.3043840527,609.6 -1.2452427405,53.3012815831,609.6 -1.2422948993,53.2983450703,609.6 -1.2388591045,53.2956056051,609.6 -1.2349718154,53.2930921862,609.6 -1.2306742488,53.2908314149,609.6 -1.2260119419,53.2888472145,609.6 -1.2210342697,53.2871605784,609.6 -1.2157939244,53.2857893497,609.6 -1.2103463594,53.2847480331,609.6 -1.2047492055,53.2840476424,609.6 -1.1990616652,53.2836955854,609.6 -1.1933438903,53.2836955854,609.6 -1.18765635,53.2840476424,609.6 -1.1820591962,53.2847480331,609.6 -1.1766116311,53.2857893497,609.6 -1.1713712859,53.2871605784,609.6 -1.1663936137,53.2888472145,609.6 -1.1617313067,53.2908314149,609.6 -1.1574337402,53.2930921862,609.6 -1.1535464511,53.2956056051,609.6 -1.1501106563,53.2983450703,609.6 -1.147162815,53.3012815831,609.6 -1.1447342412,53.3043840527,609.6 -1.142850768,53.3076196243,609.6 -1.1415324711,53.3109540261,609.6 -1.1407934505,53.3143519312,609.6 -1.1406416761,53.317777332,609.6 -1.1410788974,53.3211939204,609.6 -1.1421006189,53.3245654734,609.6 -1.1436961423,53.327856237,609.6 -1.1458486736,53.3310313059,609.6 -1.1485354967,53.3340569944,609.6 -1.1517282095,53.3369011946,609.6 -1.155393022,53.3395337186,609.6 -1.1594911116,53.3419266197,609.6 -1.1639790343,53.3440544906,609.6 -1.1688091847,53.3458947345,609.6 -1.1739303024,53.3474278065,609.6 -1.1792880176,53.348637422,609.6 -1.1848254313,53.349510731,609.6 -1.1904837226,53.3500384556,609.6 -1.1962027778,53.350214989,609.6 + + + + + + EGRU312B NETHERTHORPE RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7869" txt_name="NETHERTHORPE RWY 06"><tr><td>531712N 0011522W -<br/>531739N 0011552W -<br/>531807N 0011445W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to<br/>531740N 0011414W -<br/>531712N 0011522W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2560277778,53.2867333333,609.6 -1.2372535278,53.294504,609.6 -1.2404625371,53.2968114135,609.6 -1.2433116277,53.2992826763,609.6 -1.2457775556,53.3018976944,609.6 -1.2645416667,53.2941305556,609.6 -1.2560277778,53.2867333333,609.6 + + + + + + EGRU312C NETHERTHORPE RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="8146" txt_name="NETHERTHORPE RWY 24"><tr><td>532049N 0010813W -<br/>532022N 0010742W -<br/>531955N 0010848W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to<br/>532022N 0010918W -<br/>532049N 0010813W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1368916667,53.3468555556,609.6 -1.1551079444,53.33934775,609.6 -1.1519003867,53.3370379636,609.6 -1.1490541355,53.3345644339,609.6 -1.1465923333,53.3319473333,609.6 -1.1283666667,53.3394583333,609.6 -1.1368916667,53.3468555556,609.6 + + + + + + EGRU312D NETHERTHORPE RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7891" txt_name="NETHERTHORPE RWY 18"><tr><td>532146N 0011236W -<br/>532149N 0011142W -<br/>532101N 0011135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to<br/>532058N 0011229W -<br/>532146N 0011236W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2100472222,53.3626888889,609.6 -1.2080307222,53.3494531667,609.6 -1.2030826375,53.3499592268,609.6 -1.1980783779,53.350196059,609.6 -1.1930588056,53.35016175,609.6 -1.1950861111,53.3635027778,609.6 -1.2100472222,53.3626888889,609.6 + + + + + + EGRU312E NETHERTHORPE RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7969" txt_name="NETHERTHORPE RWY 36"><tr><td>531617N 0011052W -<br/>531614N 0011146W -<br/>531701N 0011153W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to<br/>531705N 0011059W -<br/>531617N 0011052W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1811194444,53.2714222222,609.6 -1.1831127778,53.2845884722,609.6 -1.1880312955,53.2840134665,609.6 -1.1930161911,53.28370629,609.6 -1.1980269722,53.2836694444,609.6 -1.1960444444,53.2706083333,609.6 -1.1811194444,53.2714222222,609.6 + + + + + + EGRU313A LEEDS EAST + <table border="1" cellpadding="1" cellspacing="0" row_id="7894" txt_name="LEEDS EAST"><tr><td>534837N 0011510W thence clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to<br/>534749N 0010956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to<br/>534823N 0011032W -<br/>534837N 0011510W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2527638889,53.8102666667,609.6 -1.1756111111,53.8063611111,609.6 -1.1725646884,53.8041867195,609.6 -1.1698741737,53.8018525338,609.6 -1.16752756,53.7993918007,609.6 -1.1655416667,53.7968222222,609.6 -1.1597722034,53.7985792559,609.6 -1.1543354207,53.8006786956,609.6 -1.1492480814,53.8030656328,609.6 -1.1445534596,53.8057197929,609.6 -1.1402915157,53.8086186276,609.6 -1.1364985567,53.8117375048,609.6 -1.1332069262,53.8150499175,609.6 -1.130444727,53.8185277071,609.6 -1.12823558,53.8221413022,609.6 -1.1265984186,53.8258599689,609.6 -1.1255473238,53.8296520715,609.6 -1.1250913997,53.833485341,609.6 -1.1252346899,53.8373271494,609.6 -1.1259761385,53.8411447868,609.6 -1.1273095927,53.8449057406,609.6 -1.1292238505,53.8485779722,609.6 -1.1317027504,53.8521301907,609.6 -1.1347253046,53.8555321199,609.6 -1.1382658734,53.8587547576,609.6 -1.142294381,53.8617706235,609.6 -1.1467765685,53.8645539948,609.6 -1.1516742846,53.8670811269,609.6 -1.15694581,53.869330457,609.6 -1.1625462135,53.8712827894,609.6 -1.1684277362,53.8729214607,609.6 -1.1745402006,53.8742324824,609.6 -1.1808314416,53.8752046623,609.6 -1.1872477547,53.8758296999,609.6 -1.1937343584,53.8761022585,609.6 -1.2002358655,53.8760200107,609.6 -1.2066967607,53.8755836588,609.6 -1.2130618783,53.8747969287,609.6 -1.2192768777,53.8736665375,609.6 -1.2252887108,53.8722021362,609.6 -1.231046079,53.870416226,609.6 -1.2364998728,53.8683240512,609.6 -1.2416035943,53.8659434677,609.6 -1.2463137542,53.8632947898,609.6 -1.2505902441,53.8604006154,609.6 -1.254396678,53.8572856321,609.6 -1.2577007011,53.8539764054,609.6 -1.260474264,53.8505011509,609.6 -1.262693858,53.8468894926,609.6 -1.2643407125,53.8431722097,609.6 -1.2654009498,53.8393809731,609.6 -1.2658656989,53.8355480755,609.6 -1.2657311656,53.8317061553,609.6 -1.2649986589,53.8278879192,609.6 -1.2636745748,53.8241258631,609.6 -1.2617703363,53.8204519965,609.6 -1.2593022908,53.8168975701,609.6 -1.2562915665,53.8134928111,609.6 -1.2527638889,53.8102666667,609.6 + + + + + + EGRU313B LEEDS EAST RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7787" txt_name="LEEDS EAST RWY 06"><tr><td>534803N 0011546W -<br/>534829N 0011617W -<br/>534851N 0011525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to<br/>534837N 0011510W -<br/>534835N 0011429W -<br/>534803N 0011546W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2626944444,53.8007361111,609.6 -1.2413818333,53.8096936667,609.6 -1.2527638889,53.8102666667,609.6 -1.2548809198,53.8122140415,609.6 -1.25688125,53.8142020278,609.6 -1.2714694444,53.8080694444,609.6 -1.2626944444,53.8007361111,609.6 + + + + + + EGRU313C LEEDS EAST RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7668" txt_name="LEEDS EAST RWY 24"><tr><td>535208N 0010735W -<br/>535142N 0010703W -<br/>535117N 0010802W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to<br/>535143N 0010834W -<br/>535208N 0010735W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1263416667,53.8689194444,609.6 -1.1427984167,53.8620370833,609.6 -1.1395753351,53.859719205,609.6 -1.1366436064,53.857269953,609.6 -1.1340184722,53.8547020833,609.6 -1.11755,53.8615888889,609.6 -1.1263416667,53.8689194444,609.6 + + + + + + EGRU314A DONCASTER SHEFFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="7922" txt_name="DONCASTER SHEFFIELD"><tr><td>A circle, 2.5 NM radius, centred at 532831N 0010015W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0041361111,53.5168842639,609.6 -1.0105763852,53.5167066289,609.6 -1.0169615527,53.5161752438,609.6 -1.0232369828,53.5152946553,609.6 -1.0293489916,53.5140723974,609.6 -1.0352453051,53.5125189269,609.6 -1.0408755098,53.5106475327,609.6 -1.0461914861,53.5084742213,609.6 -1.0511478222,53.5060175791,609.6 -1.0557022029,53.5032986123,609.6 -1.0598157723,53.5003405657,609.6 -1.0634534648,53.4971687231,609.6 -1.0665843034,53.49381019,609.6 -1.0691816618,53.4902936605,609.6 -1.0712234889,53.4866491717,609.6 -1.0726924933,53.4829078456,609.6 -1.0735762858,53.479101623,609.6 -1.073867481,53.4752629901,609.6 -1.0735637544,53.4714247011,609.6 -1.0726678572,53.4676194985,609.6 -1.0711875872,53.4638798337,609.6 -1.0691357169,53.460237591,609.6 -1.0665298799,53.456723816,609.6 -1.0633924162,53.4533684518,609.6 -1.0597501774,53.4502000847,609.6 -1.0556342954,53.4472457018,609.6 -1.0510799147,53.4445304622,609.6 -1.0461258912,53.4420774838,609.6 -1.0408144611,53.4399076479,609.6 -1.0351908816,53.4380394225,609.6 -1.0293030466,53.4364887065,609.6 -1.023201081,53.4352686948,609.6 -1.0169369166,53.4343897676,609.6 -1.0105638537,53.4338594025,609.6 -1.0041361111,53.4336821114,609.6 -0.9977083685,53.4338594025,609.6 -0.9913353056,53.4343897676,609.6 -0.9850711413,53.4352686948,609.6 -0.9789691756,53.4364887065,609.6 -0.9730813406,53.4380394225,609.6 -0.9674577611,53.4399076479,609.6 -0.9621463311,53.4420774838,609.6 -0.9571923075,53.4445304622,609.6 -0.9526379268,53.4472457018,609.6 -0.9485220448,53.4502000847,609.6 -0.9448798061,53.4533684518,609.6 -0.9417423423,53.456723816,609.6 -0.9391365054,53.460237591,609.6 -0.9370846351,53.4638798337,609.6 -0.935604365,53.4676194985,609.6 -0.9347084678,53.4714247011,609.6 -0.9344047413,53.4752629901,609.6 -0.9346959364,53.479101623,609.6 -0.935579729,53.4829078456,609.6 -0.9370487333,53.4866491717,609.6 -0.9390905604,53.4902936605,609.6 -0.9416879189,53.49381019,609.6 -0.9448187574,53.4971687231,609.6 -0.9484564499,53.5003405657,609.6 -0.9525700193,53.5032986123,609.6 -0.9571244001,53.5060175791,609.6 -0.9620807361,53.5084742213,609.6 -0.9673967124,53.5106475327,609.6 -0.9730269171,53.5125189269,609.6 -0.9789232306,53.5140723974,609.6 -0.9850352394,53.5152946553,609.6 -0.9913106695,53.5161752438,609.6 -0.997695837,53.5167066289,609.6 -1.0041361111,53.5168842639,609.6 + + + + + + EGRU314B DONCASTER SHEFFIELD RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8044" txt_name="DONCASTER SHEFFIELD RWY 02"><tr><td>532512N 0010132W -<br/>532522N 0010224W -<br/>532614N 0010156W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to<br/>532604N 0010105W -<br/>532512N 0010132W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0256888889,53.4200222222,609.6 -1.0179736389,53.43451025,609.6 -1.0228580729,53.4352110427,609.6 -1.0276454322,53.4361200141,609.6 -1.0323108889,53.4372324444,609.6 -1.0400194444,53.4227472222,609.6 -1.0256888889,53.4200222222,609.6 + + + + + + EGRU314C DONCASTER SHEFFIELD RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7515" txt_name="DONCASTER SHEFFIELD RWY 20"><tr><td>533150N 0005857W -<br/>533140N 0005805W -<br/>533048N 0005833W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to<br/>533058N 0005925W -<br/>533150N 0005857W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.982525,53.5305361111,609.6 -0.9902676111,53.516054,609.6 -0.9853739193,53.5153516002,609.6 -0.9805780853,53.5144406157,609.6 -0.9759051111,53.5133258056,609.6 -0.9681555556,53.5278111111,609.6 -0.982525,53.5305361111,609.6 + + + + + + EGRU315A RETFORD/GAMSTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7819" txt_name="RETFORD/GAMSTON"><tr><td>A circle, 2 NM radius, centred at 531650N 0005705W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9513888889,53.3138374154,609.6 -0.9571030807,53.3136608811,609.6 -0.9627565605,53.3131331538,609.6 -0.9682892658,53.3122598403,609.6 -0.973642426,53.3110502186,609.6 -0.9787591905,53.3095171386,609.6 -0.983585236,53.307676885,609.6 -0.9880693455,53.3055490027,609.6 -0.9921639543,53.3031560887,609.6 -0.995825655,53.3005235503,609.6 -0.9990156584,53.2976793342,609.6 -1.0017002027,53.2946536287,609.6 -1.0038509099,53.2914785415,609.6 -1.0054450831,53.2881877587,609.6 -1.0064659423,53.2848161856,609.6 -1.0069027981,53.2813995765,609.6 -1.0067511584,53.2779741546,609.6 -1.0060127711,53.2745762281,609.6 -1.0046955992,53.2712418052,609.6 -1.0028137304,53.2680062126,609.6 -1.000387223,53.2649037226,609.6 -0.9974418883,53.2619671902,609.6 -0.9940090133,53.2592277065,609.6 -0.9901250263,53.2567142704,609.6 -0.9858311092,53.2544534835,609.6 -0.9811727603,53.2524692693,609.6 -0.9761993129,53.2507826214,609.6 -0.9709634145,53.2494113829,609.6 -0.9655204716,53.2483700589,609.6 -0.9599280663,53.2476696632,609.6 -0.9542453511,53.2473176037,609.6 -0.9485324267,53.2473176037,609.6 -0.9428497114,53.2476696632,609.6 -0.9372573062,53.2483700589,609.6 -0.9318143633,53.2494113829,609.6 -0.9265784649,53.2507826214,609.6 -0.9216050175,53.2524692693,609.6 -0.9169466686,53.2544534835,609.6 -0.9126527514,53.2567142704,609.6 -0.9087687645,53.2592277065,609.6 -0.9053358895,53.2619671902,609.6 -0.9023905548,53.2649037226,609.6 -0.8999640474,53.2680062126,609.6 -0.8980821786,53.2712418052,609.6 -0.8967650066,53.2745762281,609.6 -0.8960266194,53.2779741546,609.6 -0.8958749797,53.2813995765,609.6 -0.8963118354,53.2848161856,609.6 -0.8973326947,53.2881877587,609.6 -0.8989268679,53.2914785415,609.6 -0.9010775751,53.2946536287,609.6 -0.9037621194,53.2976793342,609.6 -0.9069521227,53.3005235503,609.6 -0.9106138235,53.3031560887,609.6 -0.9147084323,53.3055490027,609.6 -0.9191925418,53.307676885,609.6 -0.9240185872,53.3095171386,609.6 -0.9291353517,53.3110502186,609.6 -0.9344885119,53.3122598403,609.6 -0.9400212173,53.3131331538,609.6 -0.9456746971,53.3136608811,609.6 -0.9513888889,53.3138374154,609.6 + + + + + + EGRU315B RETFORD/GAMSTON RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8065" txt_name="RETFORD/GAMSTON RWY 03"><tr><td>531359N 0005848W -<br/>531413N 0005937W -<br/>531509N 0005853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to<br/>531456N 0005804W -<br/>531359N 0005848W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9799194444,53.2331333333,609.6 -0.9678115,53.2487633611,609.6 -0.9725227589,53.2497798836,609.6 -0.9770623369,53.251046784,609.6 -0.9813933333,53.2525537778,609.6 -0.9934972222,53.2369222222,609.6 -0.9799194444,53.2331333333,609.6 + + + + + + EGRU315C RETFORD/GAMSTON RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7939" txt_name="RETFORD/GAMSTON RWY 21"><tr><td>531941N 0005522W -<br/>531928N 0005433W -<br/>531831N 0005517W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to<br/>531844N 0005606W -<br/>531941N 0005522W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9227055556,53.3281666667,609.6 -0.9349966667,53.3123554722,609.6 -0.9302773589,53.3113403148,609.6 -0.9257303104,53.3100743476,609.6 -0.9213926111,53.3085678889,609.6 -0.9090972222,53.3243777778,609.6 -0.9227055556,53.3281666667,609.6 + + + + + + EGRU316A SYERSTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7898" txt_name="SYERSTON"><tr><td>A circle, 2 NM radius, centred at 530124N 0005442W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9116666667,53.0566166392,609.6 -0.9173467707,53.0564400985,609.6 -0.9229665262,53.055912352,609.6 -0.9284662302,53.0550390067,609.6 -0.9337874638,53.0538293406,609.6 -0.9388737164,53.0522962039,609.6 -0.9436709894,53.0504558815,609.6 -0.9481283718,53.0483279189,609.6 -0.9521985826,53.0459349133,609.6 -0.9558384733,53.0433022727,609.6 -0.959009485,53.0404579445,609.6 -0.961678057,53.0374321177,609.6 -0.9638159791,53.0342569012,609.6 -0.9654006883,53.030965982,609.6 -0.9664155033,53.0275942667,609.6 -0.9668497966,53.0241775111,609.6 -0.9666991014,53.0207519397,609.6 -0.9659651533,53.0173538624,609.6 -0.9646558661,53.014019289,609.6 -0.9627852422,53.0107835481,609.6 -0.9603732189,53.0076809138,609.6 -0.9574454526,53.0047442428,609.6 -0.9540330431,53.0020046282,609.6 -0.9501722013,52.9994910706,609.6 -0.9459038633,52.9972301731,609.6 -0.9412732568,52.995245861,609.6 -0.9363294217,52.9935591292,609.6 -0.9311246926,52.9921878221,609.6 -0.9257141471,52.9911464456,609.6 -0.9201550256,52.9904460146,609.6 -0.9145061296,52.9900939372,609.6 -0.9088272037,52.9900939372,609.6 -0.9031783077,52.9904460146,609.6 -0.8976191863,52.9911464456,609.6 -0.8922086407,52.9921878221,609.6 -0.8870039117,52.9935591292,609.6 -0.8820600765,52.995245861,609.6 -0.87742947,52.9972301731,609.6 -0.873161132,52.9994910706,609.6 -0.8693002902,53.0020046282,609.6 -0.8658878807,53.0047442428,609.6 -0.8629601145,53.0076809138,609.6 -0.8605480911,53.0107835481,609.6 -0.8586774672,53.014019289,609.6 -0.85736818,53.0173538624,609.6 -0.8566342319,53.0207519397,609.6 -0.8564835367,53.0241775111,609.6 -0.85691783,53.0275942667,609.6 -0.8579326451,53.030965982,609.6 -0.8595173543,53.0342569012,609.6 -0.8616552764,53.0374321177,609.6 -0.8643238483,53.0404579445,609.6 -0.8674948601,53.0433022727,609.6 -0.8711347507,53.0459349133,609.6 -0.8752049615,53.0483279189,609.6 -0.8796623439,53.0504558815,609.6 -0.8844596169,53.0522962039,609.6 -0.8895458695,53.0538293406,609.6 -0.8948671031,53.0550390067,609.6 -0.9003668071,53.055912352,609.6 -0.9059865626,53.0564400985,609.6 -0.9116666667,53.0566166392,609.6 + + + + + + EGRU316B SYERSTON RWY 02L + <table border="1" cellpadding="1" cellspacing="0" row_id="7615" txt_name="SYERSTON RWY 02L"><tr><td>525833N 0005647W -<br/>525847N 0005735W -<br/>525949N 0005644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>525933N 0005557W -<br/>525833N 0005647W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9462611111,52.9757527778,609.6 -0.9326351667,52.9925465278,609.6 -0.9371605542,52.993814885,609.6 -0.9414777553,52.9953246472,609.6 -0.9455515,52.9970634722,609.6 -0.9596277778,52.9797083333,609.6 -0.9462611111,52.9757527778,609.6 + + + + + + EGRU316C SYERSTON RWY 20R + <table border="1" cellpadding="1" cellspacing="0" row_id="7654" txt_name="SYERSTON RWY 20R"><tr><td>530411N 0005312W -<br/>530356N 0005223W -<br/>530308N 0005303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530320N 0005353W -<br/>530411N 0005312W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8865611111,53.069625,609.6 -0.8979961667,53.0555806111,609.6 -0.8932158648,53.0547037456,609.6 -0.8885868653,53.0535700163,609.6 -0.8841471111,53.0521887222,609.6 -0.8731666667,53.0656694444,609.6 -0.8865611111,53.069625,609.6 + + + + + + EGRU316D SYERSTON RWY 02R + <table border="1" cellpadding="1" cellspacing="0" row_id="7767" txt_name="SYERSTON RWY 02R"><tr><td>525834N 0005641W -<br/>525848N 0005729W -<br/>525948N 0005640W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>525932N 0005553W -<br/>525834N 0005641W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9445833333,52.9761,609.6 -0.9314683889,52.9922667222,609.6 -0.9360344626,52.9934709154,609.6 -0.9404020882,52.9949186579,609.6 -0.9445356667,52.9965981667,609.6 -0.9579527778,52.9800527778,609.6 -0.9445833333,52.9761,609.6 + + + + + + EGRU316E SYERSTON RWY 20L + <table border="1" cellpadding="1" cellspacing="0" row_id="7936" txt_name="SYERSTON RWY 20L"><tr><td>530411N 0005306W -<br/>530357N 0005218W -<br/>530307N 0005259W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530319N 0005348W -<br/>530411N 0005306W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8850333333,53.0698027778,609.6 -0.8967719444,53.0553830278,609.6 -0.8920324996,53.0544416819,609.6 -0.8874536336,53.0532462932,609.6 -0.8830727778,53.0518066389,609.6 -0.8716361111,53.06585,609.6 -0.8850333333,53.0698027778,609.6 + + + + + + EGRU316F SYERSTON RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8158" txt_name="SYERSTON RWY 06"><tr><td>525941N 0005911W -<br/>530010N 0005936W -<br/>530043N 0005749W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530015N 0005724W -<br/>525941N 0005911W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9864583333,52.9947277778,609.6 -0.9567,53.0040936667,609.6 -0.9593936936,53.0066201301,609.6 -0.9616990915,53.0092827496,609.6 -0.9635973611,53.0120598611,609.6 -0.9933361111,53.0027,609.6 -0.9864583333,52.9947277778,609.6 + + + + + + EGRU316G SYERSTON RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7842" txt_name="SYERSTON RWY 24"><tr><td>530305N 0005018W -<br/>530236N 0004953W -<br/>530204N 0005135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530233N 0005200W -<br/>530305N 0005018W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8383527778,53.0513527778,609.6 -0.8665545278,53.0425228056,609.6 -0.8638693662,53.0399925578,609.6 -0.8615739082,53.0373266633,609.6 -0.8596867778,53.0345468611,609.6 -0.8314638889,53.0433833333,609.6 -0.8383527778,53.0513527778,609.6 + + + + + + EGRU316H SYERSTON RWY 06L + <table border="1" cellpadding="1" cellspacing="0" row_id="7989" txt_name="SYERSTON RWY 06L"><tr><td>525945N 0005907W -<br/>530013N 0005931W -<br/>530045N 0005750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530016N 0005726W -<br/>525945N 0005907W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9851694444,52.9957,609.6 -0.9571801944,53.0045089444,609.6 -0.959810169,53.0070601033,609.6 -0.9620483698,53.0097438645,609.6 -0.9638765,53.0125383889,609.6 -0.9920472222,53.0036722222,609.6 -0.9851694444,52.9957,609.6 + + + + + + EGRU316I SYERSTON RWY 24R + <table border="1" cellpadding="1" cellspacing="0" row_id="8190" txt_name="SYERSTON RWY 24R"><tr><td>530301N 0005038W -<br/>530232N 0005013W -<br/>530206N 0005136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530235N 0005201W -<br/>530301N 0005038W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8438194444,53.0502083333,609.6 -0.8670451944,53.0429354444,609.6 -0.8642959963,53.0404299106,609.6 -0.8619331102,53.0377851374,609.6 -0.8599757222,53.0350226944,609.6 -0.8369305556,53.0422388889,609.6 -0.8438194444,53.0502083333,609.6 + + + + + + EGRU316J SYERSTON RWY 06R + <table border="1" cellpadding="1" cellspacing="0" row_id="8111" txt_name="SYERSTON RWY 06R"><tr><td>525942N 0005904W -<br/>530010N 0005929W -<br/>530042N 0005748W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530014N 0005723W -<br/>525942N 0005904W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9844611111,52.9948861111,609.6 -0.9562944167,53.0037530833,609.6 -0.9590402789,53.0062585353,609.6 -0.961400833,53.0089030482,609.6 -0.9633568056,53.0116651111,609.6 -0.9913388889,53.0028555556,609.6 -0.9844611111,52.9948861111,609.6 + + + + + + EGRU316K SYERSTON RWY 24L + <table border="1" cellpadding="1" cellspacing="0" row_id="7972" txt_name="SYERSTON RWY 24L"><tr><td>530256N 0005042W -<br/>530227N 0005017W -<br/>530203N 0005134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530232N 0005158W -<br/>530256N 0005042W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8450555556,53.0487972222,609.6 -0.8661643611,53.0421849444,609.6 -0.8635312747,53.0396347292,609.6 -0.8612906516,53.0369517821,609.6 -0.8594606944,53.0341579722,609.6 -0.8381666667,53.0408277778,609.6 -0.8450555556,53.0487972222,609.6 + + + + + + EGRU316L SYERSTON RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7642" txt_name="SYERSTON RWY 11"><tr><td>530158N 0005936W -<br/>530229N 0005919W -<br/>530210N 0005745W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530139N 0005759W -<br/>530158N 0005936W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9932277778,53.0327916667,609.6 -0.9664401111,53.0274773611,609.6 -0.9655974504,53.0304427487,609.6 -0.9643139209,53.0333501353,609.6 -0.9625999167,53.03617575,609.6 -0.9885555556,53.041325,609.6 -0.9932277778,53.0327916667,609.6 + + + + + + EGRU316M SYERSTON RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7760" txt_name="SYERSTON RWY 29"><tr><td>530042N 0005021W -<br/>530011N 0005038W -<br/>530025N 0005149W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530055N 0005129W -<br/>530042N 0005021W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8391277778,53.0115861111,609.6 -0.8580746667,53.0153695556,609.6 -0.8594877637,53.0124841721,609.6 -0.8613268855,53.0096875054,609.6 -0.8635769444,53.0070023889,609.6 -0.8437972222,53.0030527778,609.6 -0.8391277778,53.0115861111,609.6 + + + + + + EGRU316N SYERSTON RWY 11L + <table border="1" cellpadding="1" cellspacing="0" row_id="7588" txt_name="SYERSTON RWY 11L"><tr><td>530201N 0005937W -<br/>530231N 0005921W -<br/>530212N 0005744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530141N 0005759W -<br/>530201N 0005937W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9937388889,53.0334777778,609.6 -0.9663150833,53.0280407778,609.6 -0.965389513,53.0309945302,609.6 -0.9640255096,53.0338858783,609.6 -0.9622341111,53.0366912222,609.6 -0.9890666667,53.0420111111,609.6 -0.9937388889,53.0334777778,609.6 + + + + + + EGRU316O SYERSTON RWY 29R + <table border="1" cellpadding="1" cellspacing="0" row_id="8183" txt_name="SYERSTON RWY 29R"><tr><td>530038N 0004954W -<br/>530008N 0005010W -<br/>530027N 0005147W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530057N 0005128W -<br/>530038N 0004954W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8315305556,53.0106722222,609.6 -0.8578550556,53.0159266944,609.6 -0.8591842718,53.0130296541,609.6 -0.8609412357,53.0102167252,609.6 -0.8631115556,53.0075108333,609.6 -0.8361972222,53.0021388889,609.6 -0.8315305556,53.0106722222,609.6 + + + + + + EGRU316P SYERSTON RWY 11R + <table border="1" cellpadding="1" cellspacing="0" row_id="7952" txt_name="SYERSTON RWY 11R"><tr><td>530157N 0005940W -<br/>530228N 0005923W -<br/>530209N 0005747W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530137N 0005800W -<br/>530157N 0005940W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9944416667,53.0324972222,609.6 -0.9665396667,53.0269653611,609.6 -0.9657723513,53.029941211,609.6 -0.9645618371,53.0328630501,609.6 -0.9629179722,53.0357069444,609.6 -0.9897694444,53.0410305556,609.6 -0.9944416667,53.0324972222,609.6 + + + + + + EGRU316Q SYERSTON RWY 29L + <table border="1" cellpadding="1" cellspacing="0" row_id="7610" txt_name="SYERSTON RWY 29L"><tr><td>530034N 0004949W -<br/>530003N 0005006W -<br/>530024N 0005150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530054N 0005130W -<br/>530034N 0004949W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8303138889,53.0093083333,609.6 -0.8582771389,53.0148901944,609.6 -0.8597627878,53.0120150787,609.6 -0.8616730086,53.0092326862,609.6 -0.8639921111,53.0065657778,609.6 -0.8349805556,53.000775,609.6 -0.8303138889,53.0093083333,609.6 + + + + + + EGRU316R SYERSTON RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7623" txt_name="SYERSTON RWY 15"><tr><td>530357N 0005715W -<br/>530413N 0005628W -<br/>530319N 0005538W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530306N 0005627W -<br/>530357N 0005715W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9541083333,53.0658666667,609.6 -0.9407998056,53.0516073056,609.6 -0.9364328997,53.0530812795,609.6 -0.9318622098,53.054310836,609.6 -0.9271253333,53.0552858611,609.6 -0.9411,53.0702638889,609.6 -0.9541083333,53.0658666667,609.6 + + + + + + EGRU316S SYERSTON RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7661" txt_name="SYERSTON RWY 33"><tr><td>525859N 0005135W -<br/>525843N 0005222W -<br/>525937N 0005312W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>525955N 0005228W -<br/>525859N 0005135W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8598138889,52.9829722222,609.6 -0.8744734444,52.9987451111,609.6 -0.8783162842,52.9968158968,609.6 -0.8824324816,52.995104339,609.6 -0.8867882778,52.9936244722,609.6 -0.8727944444,52.9785722222,609.6 -0.8598138889,52.9829722222,609.6 + + + + + + EGRU316T SYERSTON RWY 15L + <table border="1" cellpadding="1" cellspacing="0" row_id="7873" txt_name="SYERSTON RWY 15L"><tr><td>530354N 0005709W -<br/>530410N 0005622W -<br/>530320N 0005534W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530307N 0005624W -<br/>530354N 0005709W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9523777778,53.0651111111,609.6 -0.9400369167,53.0518878056,609.6 -0.935623392,53.0533211891,609.6 -0.9310120734,53.0545073484,609.6 -0.9262410278,53.0554365,609.6 -0.9393694444,53.0695083333,609.6 -0.9523777778,53.0651111111,609.6 + + + + + + EGRU316U SYERSTON RWY 33R + <table border="1" cellpadding="1" cellspacing="0" row_id="7651" txt_name="SYERSTON RWY 33R"><tr><td>525857N 0005130W -<br/>525841N 0005217W -<br/>525938N 0005310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>525957N 0005226W -<br/>525857N 0005130W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8583611111,52.9825083333,609.6 -0.8738008056,52.9991213611,609.6 -0.8775965703,52.9971507599,609.6 -0.8816725553,52.9953958037,609.6 -0.8859951944,52.9938709167,609.6 -0.8713416667,52.9781083333,609.6 -0.8583611111,52.9825083333,609.6 + + + + + + EGRU316V SYERSTON RWY 15R + <table border="1" cellpadding="1" cellspacing="0" row_id="7759" txt_name="SYERSTON RWY 15R"><tr><td>530355N 0005717W -<br/>530411N 0005630W -<br/>530318N 0005541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>530305N 0005630W -<br/>530355N 0005717W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9546638889,53.0653361111,609.6 -0.94156925,53.0513138889,609.6 -0.9372483332,53.0528294872,609.6 -0.9327174011,53.0541032867,609.6 -0.9280136389,53.0551248333,609.6 -0.9416555556,53.0697388889,609.6 -0.9546638889,53.0653361111,609.6 + + + + + + EGRU316W SYERSTON RWY 33L + <table border="1" cellpadding="1" cellspacing="0" row_id="7981" txt_name="SYERSTON RWY 33L"><tr><td>525901N 0005141W -<br/>525845N 0005228W -<br/>525936N 0005315W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to<br/>525954N 0005231W -<br/>525901N 0005141W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8614138889,52.9836138889,609.6 -0.8751460278,52.9983811389,609.6 -0.8790351997,52.9964925478,609.6 -0.8831911022,52.9948236641,609.6 -0.88757975,52.9933881389,609.6 -0.8743916667,52.9792111111,609.6 -0.8614138889,52.9836138889,609.6 + + + + + + EGRU317A SANDTOFT + <table border="1" cellpadding="1" cellspacing="0" row_id="7553" txt_name="SANDTOFT"><tr><td>A circle, 2 NM radius, centred at 533335N 0005130W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8583333333,53.5930025171,609.6 -0.8640851205,53.5928259897,609.6 -0.8697757947,53.5922982831,609.6 -0.8753448971,53.5914250039,609.6 -0.880733269,53.5902154301,609.6 -0.8858836849,53.5886824113,609.6 -0.8907414633,53.5868422319,609.6 -0.8952550498,53.5847144365,609.6 -0.8993765668,53.5823216214,609.6 -0.9030623216,53.5796891934,609.6 -0.9062732702,53.5768450985,609.6 -0.9089754301,53.5738195239,609.6 -0.9111402376,53.5706445766,609.6 -0.9127448481,53.5673539412,609.6 -0.913772373,53.5639825219,609.6 -0.9142120544,53.5605660714,609.6 -0.9140593727,53.5571408114,609.6 -0.9133160892,53.5537430482,609.6 -0.9119902209,53.5504087882,609.6 -0.91009595,53.5471733563,609.6 -0.907653468,53.5440710226,609.6 -0.9046887571,53.5411346403,609.6 -0.9012333109,53.5383952985,609.6 -0.8973237974,53.5358819942,609.6 -0.8930016694,53.5336213271,609.6 -0.8883127239,53.531637219,609.6 -0.8833066178,53.5299506621,609.6 -0.8780363436,53.5285794981,609.6 -0.8725576704,53.5275382309,609.6 -0.8669285573,53.5268378737,609.6 -0.8612085435,53.5264858335,609.6 -0.8554581231,53.5264858335,609.6 -0.8497381094,53.5268378737,609.6 -0.8441089963,53.5275382309,609.6 -0.8386303231,53.5285794981,609.6 -0.8333600489,53.5299506621,609.6 -0.8283539428,53.531637219,609.6 -0.8236649972,53.5336213271,609.6 -0.8193428692,53.5358819942,609.6 -0.8154333558,53.5383952985,609.6 -0.8119779095,53.5411346403,609.6 -0.8090131987,53.5440710226,609.6 -0.8065707167,53.5471733563,609.6 -0.8046764458,53.5504087882,609.6 -0.8033505775,53.5537430482,609.6 -0.802607294,53.5571408114,609.6 -0.8024546123,53.5605660714,609.6 -0.8028942936,53.5639825219,609.6 -0.8039218186,53.5673539412,609.6 -0.805526429,53.5706445766,609.6 -0.8076912366,53.5738195239,609.6 -0.8103933964,53.5768450985,609.6 -0.8136043451,53.5796891934,609.6 -0.8172900999,53.5823216214,609.6 -0.8214116168,53.5847144365,609.6 -0.8259252034,53.5868422319,609.6 -0.8307829817,53.5886824113,609.6 -0.8359333976,53.5902154301,609.6 -0.8413217696,53.5914250039,609.6 -0.8468908719,53.5922982831,609.6 -0.8525815462,53.5928259897,609.6 -0.8583333333,53.5930025171,609.6 + + + + + + EGRU317B SANDTOFT RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7640" txt_name="SANDTOFT RWY 05"><tr><td>533118N 0005438W -<br/>533141N 0005517W -<br/>533222N 0005409W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to<br/>533159N 0005330W -<br/>533118N 0005438W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.91055,53.5216333333,609.6 -0.8917588611,53.5330525556,609.6 -0.8956587241,53.5349549572,609.6 -0.899255258,53.537058912,609.6 -0.9025191667,53.5393473333,609.6 -0.9213083333,53.5279277778,609.6 -0.91055,53.5216333333,609.6 + + + + + + EGRU317C SANDTOFT RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7750" txt_name="SANDTOFT RWY 23"><tr><td>533547N 0004830W -<br/>533525N 0004751W -<br/>533448N 0004851W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to<br/>533511N 0004930W -<br/>533547N 0004830W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8082888889,53.5964805556,609.6 -0.8249266389,53.5864094444,609.6 -0.8210211529,53.5845080996,609.6 -0.8174199324,53.5824049166,609.6 -0.8141522778,53.5801170556,609.6 -0.7975111111,53.5901888889,609.6 -0.8082888889,53.5964805556,609.6 + + + + + + EGRU319A WADDINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7717" txt_name="WADDINGTON"><tr><td>A circle, 2.5 NM radius, centred at 530958N 0003126W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5238888889,53.2077142103,609.6 -0.5302827139,53.207536568,609.6 -0.5366218315,53.207005161,609.6 -0.5428520067,53.2061245359,609.6 -0.5489199443,53.204902227,609.6 -0.5547737486,53.2033486911,609.6 -0.5603633708,53.2014772172,609.6 -0.5656410391,53.1993038121,609.6 -0.5705616695,53.1968470626,609.6 -0.5750832522,53.194127975,609.6 -0.5791672108,53.1911697949,609.6 -0.582778732,53.1879978065,609.6 -0.5858870608,53.1846391161,609.6 -0.5884657617,53.1811224189,609.6 -0.5904929406,53.1774777527,609.6 -0.5919514285,53.1737362408,609.6 -0.5928289237,53.1699298254,609.6 -0.5931180914,53.1660909943,609.6 -0.5928166217,53.1622525033,609.6 -0.5919272434,53.1584470964,609.6 -0.5904576959,53.1547072272,609.6 -0.5884206578,53.1510647819,609.6 -0.5858336336,53.1475508082,609.6 -0.5827188008,53.1441952511,609.6 -0.5791028166,53.1410266992,609.6 -0.5750165877,53.1380721416,609.6 -0.5704950051,53.1353567393,609.6 -0.5655766448,53.1329036124,609.6 -0.5603034396,53.1307336437,609.6 -0.5547203213,53.1288653031,609.6 -0.5488748403,53.1273144907,609.6 -0.542816762,53.1260944027,609.6 -0.5365976464,53.1252154203,609.6 -0.5302704118,53.1246850218,609.6 -0.5238888889,53.1245077195,609.6 -0.517507366,53.1246850218,609.6 -0.5111801314,53.1252154203,609.6 -0.5049610157,53.1260944027,609.6 -0.4989029375,53.1273144907,609.6 -0.4930574565,53.1288653031,609.6 -0.4874743382,53.1307336437,609.6 -0.4822011329,53.1329036124,609.6 -0.4772827727,53.1353567393,609.6 -0.4727611901,53.1380721416,609.6 -0.4686749612,53.1410266992,609.6 -0.465058977,53.1441952511,609.6 -0.4619441442,53.1475508082,609.6 -0.45935712,53.1510647819,609.6 -0.4573200818,53.1547072272,609.6 -0.4558505344,53.1584470964,609.6 -0.4549611561,53.1622525033,609.6 -0.4546596863,53.1660909943,609.6 -0.4549488541,53.1699298254,609.6 -0.4558263492,53.1737362408,609.6 -0.4572848372,53.1774777527,609.6 -0.4593120161,53.1811224189,609.6 -0.4618907169,53.1846391161,609.6 -0.4649990458,53.1879978065,609.6 -0.468610567,53.1911697949,609.6 -0.4726945256,53.194127975,609.6 -0.4772161083,53.1968470626,609.6 -0.4821367386,53.1993038121,609.6 -0.487414407,53.2014772172,609.6 -0.4930040291,53.2033486911,609.6 -0.4988578335,53.204902227,609.6 -0.504925771,53.2061245359,609.6 -0.5111559462,53.207005161,609.6 -0.5174950639,53.207536568,609.6 -0.5238888889,53.2077142103,609.6 + + + + + + EGRU319B WADDINGTON RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8137" txt_name="WADDINGTON RWY 02"><tr><td>530639N 0003308W -<br/>530651N 0003358W -<br/>530746N 0003322W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to<br/>530734N 0003233W -<br/>530639N 0003308W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5523125556,53.1109521111,609.6 -0.54236325,53.1260178611,609.6 -0.5471194495,53.1269222092,609.6 -0.5517551548,53.1280302058,609.6 -0.5562463056,53.1293361111,609.6 -0.5661892778,53.1142725833,609.6 -0.5523125556,53.1109521111,609.6 + + + + + + EGRU319C WADDINGTON RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="8024" txt_name="WADDINGTON RWY 20"><tr><td>531313N 0002946W -<br/>531301N 0002856W -<br/>531210N 0002929W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to<br/>531222N 0003019W -<br/>531313N 0002946W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4960258889,53.2203266667,609.6 -0.5053914167,53.2062031111,609.6 -0.5006270692,53.2052975907,609.6 -0.4959840364,53.2041880917,609.6 -0.4914865278,53.2028803889,609.6 -0.4821149167,53.21700625,609.6 -0.4960258889,53.2203266667,609.6 + + + + + + EGRU320A CRANWELL + <table border="1" cellpadding="1" cellspacing="0" row_id="8010" txt_name="CRANWELL"><tr><td>A circle, 2.5 NM radius, centred at 530147N 0002934W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4927527778,53.0713373914,609.6 -0.4991263854,53.0711597458,609.6 -0.5054454595,53.070628329,609.6 -0.5116559371,53.0697476878,609.6 -0.5177046922,53.0685253563,609.6 -0.523539994,53.0669717913,609.6 -0.5291119522,53.0651002821,609.6 -0.5343729466,53.0629268355,609.6 -0.5392780356,53.0604700383,609.6 -0.5437853424,53.0577508973,609.6 -0.5478564126,53.054792658,609.6 -0.5514565422,53.0516206051,609.6 -0.5545550733,53.0482618451,609.6 -0.557125653,53.0447450735,609.6 -0.5591464559,53.0411003288,609.6 -0.5606003663,53.0373587348,609.6 -0.5614751202,53.0335522342,609.6 -0.5617634053,53.0297133154,609.6 -0.5614629176,53.025874735,609.6 -0.5605763766,53.0220692379,609.6 -0.559111496,53.0183292784,609.6 -0.5570809135,53.0146867436,609.6 -0.5545020777,53.011172682,609.6 -0.5513970952,53.0078170398,609.6 -0.5477925386,53.0046484063,609.6 -0.5437192166,53.0016937715,609.6 -0.5392119097,52.9989782975,609.6 -0.5343090725,52.996525105,609.6 -0.5290525052,52.9943550778,609.6 -0.5234869983,52.9924866863,609.6 -0.5176599526,52.9909358313,609.6 -0.5116209771,52.9897157097,609.6 -0.5054214697,52.988836703,609.6 -0.4991141827,52.9883062898,609.6 -0.4927527778,52.9881289825,609.6 -0.4863913728,52.9883062898,609.6 -0.4800840859,52.988836703,609.6 -0.4738845785,52.9897157097,609.6 -0.467845603,52.9909358313,609.6 -0.4620185572,52.9924866863,609.6 -0.4564530504,52.9943550778,609.6 -0.4511964831,52.996525105,609.6 -0.4462936458,52.9989782975,609.6 -0.441786339,53.0016937715,609.6 -0.437713017,53.0046484063,609.6 -0.4341084603,53.0078170398,609.6 -0.4310034778,53.011172682,609.6 -0.428424642,53.0146867436,609.6 -0.4263940595,53.0183292784,609.6 -0.424929179,53.0220692379,609.6 -0.424042638,53.025874735,609.6 -0.4237421503,53.0297133154,609.6 -0.4240304353,53.0335522342,609.6 -0.4249051893,53.0373587348,609.6 -0.4263590997,53.0411003288,609.6 -0.4283799025,53.0447450735,609.6 -0.4309504822,53.0482618451,609.6 -0.4340490133,53.0516206051,609.6 -0.437649143,53.054792658,609.6 -0.4417202131,53.0577508973,609.6 -0.4462275199,53.0604700383,609.6 -0.451132609,53.0629268355,609.6 -0.4563936033,53.0651002821,609.6 -0.4619655615,53.0669717913,609.6 -0.4678008634,53.0685253563,609.6 -0.4738496185,53.0697476878,609.6 -0.4800600961,53.070628329,609.6 -0.4863791702,53.0711597458,609.6 -0.4927527778,53.0713373914,609.6 + + + + + + EGRU320B CRANWELL RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="8187" txt_name="CRANWELL RWY 01"><tr><td>525833N 0002919W -<br/>525838N 0003012W -<br/>525918N 0003003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>525918N 0002909W -<br/>525833N 0002919W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4886638889,52.9759416667,609.6 -0.4857053333,52.9883466944,609.6 -0.4907135656,52.9881471692,609.6 -0.4957325729,52.9881678233,609.6 -0.5007358333,52.9884085556,609.6 -0.5034,52.9772222222,609.6 -0.4886638889,52.9759416667,609.6 + + + + + + EGRU320C CRANWELL RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="7695" txt_name="CRANWELL RWY 19"><tr><td>530445N 0002845W -<br/>530440N 0002751W -<br/>530406N 0002800W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530415N 0002852W -<br/>530445N 0002845W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4790694444,53.0791638889,609.6 -0.4810846389,53.0707389722,609.6 -0.4761629955,53.0701185314,609.6 -0.4713295119,53.0692838807,609.6 -0.4666098611,53.0682394722,609.6 -0.4643,53.0778833333,609.6 -0.4790694444,53.0791638889,609.6 + + + + + + EGRU320D CRANWELL RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7747" txt_name="CRANWELL RWY 08"><tr><td>530107N 0003443W -<br/>530139N 0003450W -<br/>530144N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530112N 0003335W -<br/>530107N 0003443W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5786777778,53.0185333333,609.6 -0.559841,53.0200006389,609.6 -0.5608322154,53.0229411873,609.6 -0.5614694696,53.0259171598,609.6 -0.5617493611,53.0289130833,609.6 -0.5805666667,53.0274472222,609.6 -0.5786777778,53.0185333333,609.6 + + + + + + EGRU320E CRANWELL RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7762" txt_name="CRANWELL RWY 26"><tr><td>530227N 0002421W -<br/>530155N 0002414W -<br/>530150N 0002526W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530222N 0002532W -<br/>530227N 0002421W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4057472222,53.0409472222,609.6 -0.4256331389,53.0394249444,609.6 -0.4246510812,53.0364830877,609.6 -0.4240234784,53.0335062108,609.6 -0.4237535278,53.0305098056,609.6 -0.40385,53.0320333333,609.6 -0.4057472222,53.0409472222,609.6 + + + + + + EGRU320F CRANWELL RWY 08N + <table border="1" cellpadding="1" cellspacing="0" row_id="8128" txt_name="CRANWELL RWY 08N"><tr><td>530107N 0003416W -<br/>530139N 0003423W -<br/>530142N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530110N 0003335W -<br/>530107N 0003416W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5711777778,53.01855,609.6 -0.55959675,53.0194088611,609.6 -0.560659422,53.022340648,609.6 -0.5613689532,53.025310992,609.6 -0.5617215833,53.0283044444,609.6 -0.5729805556,53.0274694444,609.6 -0.5711777778,53.01855,609.6 + + + + + + EGRU320G CRANWELL RWY 26N + <table border="1" cellpadding="1" cellspacing="0" row_id="7733" txt_name="CRANWELL RWY 26N"><tr><td>530221N 0002450W -<br/>530149N 0002443W -<br/>530146N 0002525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530218N 0002531W -<br/>530221N 0002450W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4137722222,53.039175,609.6 -0.4252282222,53.0383400278,609.6 -0.4243769461,53.0353831851,609.6 -0.4238815851,53.0323970413,609.6 -0.4237446389,53.0293971389,609.6 -0.4119666667,53.0302555556,609.6 -0.4137722222,53.039175,609.6 + + + + + + EGRU320H CRANWELL RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7547" txt_name="CRANWELL RWY 06"><tr><td>530100N 0003352W -<br/>530129N 0003415W -<br/>530139N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530106N 0003333W -<br/>530100N 0003352W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5643539444,53.0167546667,609.6 -0.559089,53.0182818889,609.6 -0.56032936,53.0213150389,609.6 -0.5611889152,53.0243957527,609.6 -0.56166275,53.0275066667,609.6 -0.5708006667,53.0248561111,609.6 -0.5643539444,53.0167546667,609.6 + + + + + + EGRU320I CRANWELL RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7551" txt_name="CRANWELL RWY 24"><tr><td>530406N 0002513W -<br/>530337N 0002450W -<br/>530314N 0002611W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530339N 0002648W -<br/>530406N 0002513W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4202738333,53.0683875833,609.6 -0.4467458333,53.0607521667,609.6 -0.4430133857,53.0585835142,609.6 -0.439561951,53.0562521411,609.6 -0.4364109722,53.0537712222,609.6 -0.4138206111,53.0602862222,609.6 -0.4202738333,53.0683875833,609.6 + + + + + + EGRU320K CRANWELL RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7897" txt_name="CRANWELL RWY 21"><tr><td>530519N 0002721W -<br/>530503N 0002635W -<br/>530359N 0002737W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to<br/>530411N 0002828W -<br/>530519N 0002721W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4558644444,53.08874525,609.6 -0.4743584167,53.0698336944,609.6 -0.4695525918,53.0689181653,609.6 -0.4648706423,53.0677938034,609.6 -0.4603375556,53.0664666111,609.6 -0.4430011389,53.0841885,609.6 -0.4558644444,53.08874525,609.6 + + + + + + EGRU321A HUMBERSIDE + <table border="1" cellpadding="1" cellspacing="0" row_id="7763" txt_name="HUMBERSIDE"><tr><td>A circle, 2.5 NM radius, centred at 533424N 0002105W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3514583333,53.6150307992,609.6 -0.3579135341,53.6148531665,609.6 -0.3643135,53.6143217883,609.6 -0.370603473,53.6134412113,609.6 -0.3767296443,53.6122189696,609.6 -0.3826396183,53.6106655197,609.6 -0.3882828644,53.6087941506,609.6 -0.3936111511,53.6066208689,609.6 -0.3985789612,53.6041642607,609.6 -0.4031438817,53.601445332,609.6 -0.4072669666,53.5984873276,609.6 -0.4109130692,53.5953155311,609.6 -0.4140511412,53.5919570477,609.6 -0.4166544952,53.5884405714,609.6 -0.4187010295,53.5847961387,609.6 -0.4201734131,53.5810548714,609.6 -0.4210592292,53.5772487098,609.6 -0.4213510757,53.5734101397,609.6 -0.4210466237,53.5695719148,609.6 -0.4201486315,53.5657667769,609.6 -0.4186649156,53.5620271769,609.6 -0.4166082789,53.5583849984,609.6 -0.4139963963,53.5548712864,609.6 -0.41085166,53.5515159834,609.6 -0.4072009842,53.5483476749,609.6 -0.4030755731,53.5453933474,609.6 -0.3985106526,53.5426781594,609.6 -0.3935451687,53.5402252281,609.6 -0.388221455,53.5380554343,609.6 -0.3825848733,53.5361872456,609.6 -0.3766834279,53.5346365601,609.6 -0.3705673591,53.5334165726,609.6 -0.3642887183,53.5325376629,609.6 -0.3579009286,53.5320073084,609.6 -0.3514583333,53.5318300209,609.6 -0.3450157381,53.5320073084,609.6 -0.3386279483,53.5325376629,609.6 -0.3323493076,53.5334165726,609.6 -0.3262332388,53.5346365601,609.6 -0.3203317933,53.5361872456,609.6 -0.3146952116,53.5380554343,609.6 -0.309371498,53.5402252281,609.6 -0.304406014,53.5426781594,609.6 -0.2998410935,53.5453933474,609.6 -0.2957156825,53.5483476749,609.6 -0.2920650067,53.5515159834,609.6 -0.2889202703,53.5548712864,609.6 -0.2863083878,53.5583849984,609.6 -0.284251751,53.5620271769,609.6 -0.2827680351,53.5657667769,609.6 -0.2818700429,53.5695719148,609.6 -0.281565591,53.5734101397,609.6 -0.2818574375,53.5772487098,609.6 -0.2827432535,53.5810548714,609.6 -0.2842156372,53.5847961387,609.6 -0.2862621715,53.5884405714,609.6 -0.2888655254,53.5919570477,609.6 -0.2920035974,53.5953155311,609.6 -0.2956497001,53.5984873276,609.6 -0.299772785,53.601445332,609.6 -0.3043377054,53.6041642607,609.6 -0.3093055156,53.6066208689,609.6 -0.3146338023,53.6087941506,609.6 -0.3202770483,53.6106655197,609.6 -0.3261870224,53.6122189696,609.6 -0.3323131937,53.6134412113,609.6 -0.3386031667,53.6143217883,609.6 -0.3450031326,53.6148531665,609.6 -0.3514583333,53.6150307992,609.6 + + + + + + EGRU321B HUMBERSIDE RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="7616" txt_name="HUMBERSIDE RWY 02"><tr><td>533119N 0002244W -<br/>533132N 0002334W -<br/>533213N 0002305W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to<br/>533201N 0002215W -<br/>533119N 0002244W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3787722222,53.5220722222,609.6 -0.3709044722,53.5334741944,609.6 -0.3756882022,53.5344122774,609.6 -0.380346243,53.5355531468,609.6 -0.3848544167,53.5368908889,609.6 -0.3927166667,53.5254916667,609.6 -0.3787722222,53.5220722222,609.6 + + + + + + EGRU321C HUMBERSIDE RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7706" txt_name="HUMBERSIDE RWY 20"><tr><td>533729N 0001927W -<br/>533717N 0001836W -<br/>533636N 0001905W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to<br/>533648N 0001955W -<br/>533729N 0001927W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3240805556,53.6247805556,609.6 -0.33197675,53.6133836944,609.6 -0.3271853186,53.6124439859,609.6 -0.32252048,53.6113011963,609.6 -0.3180065556,53.6099612778,609.6 -0.3101027778,53.6213638889,609.6 -0.3240805556,53.6247805556,609.6 + + + + + + EGRU321D HUMBERSIDE RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7528" txt_name="HUMBERSIDE RWY 08"><tr><td>533356N 0002538W -<br/>533428N 0002545W -<br/>533430N 0002517W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to<br/>533358N 0002513W -<br/>533356N 0002538W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.4272916667,53.5654611111,609.6 -0.4202290833,53.5660261111,609.6 -0.420950153,53.5690011489,609.6 -0.4213085477,53.5719994114,609.6 -0.4213023056,53.57500525,609.6 -0.4292833333,53.5743666667,609.6 -0.4272916667,53.5654611111,609.6 + + + + + + EGRU321E HUMBERSIDE RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8079" txt_name="HUMBERSIDE RWY 26"><tr><td>533513N 0001609W -<br/>533441N 0001602W -<br/>533437N 0001655W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to<br/>533509N 0001705W -<br/>533513N 0001609W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2691388889,53.587075,609.6 -0.2847413611,53.5858466111,609.6 -0.2834108694,53.5829460348,609.6 -0.2824360879,53.5799958388,609.6 -0.2818220278,53.5770114444,609.6 -0.2671444444,53.5781666667,609.6 -0.2691388889,53.587075,609.6 + + + + + + EGRU322A WICKENBY + <table border="1" cellpadding="1" cellspacing="0" row_id="8054" txt_name="WICKENBY"><tr><td>A circle, 2 NM radius, centred at 531901N 0002056W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3487972222,53.3502177668,609.6 -0.3545162778,53.3500412334,609.6 -0.3601745694,53.3495135088,609.6 -0.3657119835,53.3486401997,609.6 -0.371069699,53.3474305843,609.6 -0.376190817,53.3458975123,609.6 -0.3810209678,53.3440572683,609.6 -0.3855088908,53.3419293974,609.6 -0.3896069807,53.3395364964,609.6 -0.3932717934,53.3369039724,609.6 -0.3964645064,53.3340597721,609.6 -0.3991513297,53.3310340837,609.6 -0.4013038611,53.3278590148,609.6 -0.4028993846,53.3245682512,609.6 -0.4039211062,53.3211966981,609.6 -0.4043583275,53.3177801097,609.6 -0.4042065531,53.314354709,609.6 -0.4034675324,53.3109568038,609.6 -0.4021492354,53.3076224021,609.6 -0.4002657622,53.3043868305,609.6 -0.3978371881,53.3012843609,609.6 -0.3948893467,53.2983478481,609.6 -0.3914535517,53.2956083828,609.6 -0.3875662623,53.293094964,609.6 -0.3832686955,53.2908341927,609.6 -0.3786063882,53.2888499923,609.6 -0.3736287158,53.2871633562,609.6 -0.3683883701,53.2857921275,609.6 -0.3629408047,53.2847508108,609.6 -0.3573436505,53.2840504202,609.6 -0.3516561099,53.2836983632,609.6 -0.3459383346,53.2836983632,609.6 -0.3402507939,53.2840504202,609.6 -0.3346536397,53.2847508108,609.6 -0.3292060743,53.2857921275,609.6 -0.3239657287,53.2871633562,609.6 -0.3189880562,53.2888499923,609.6 -0.3143257489,53.2908341927,609.6 -0.3100281821,53.293094964,609.6 -0.3061408928,53.2956083828,609.6 -0.3027050977,53.2983478481,609.6 -0.2997572563,53.3012843609,609.6 -0.2973286823,53.3043868305,609.6 -0.295445209,53.3076224021,609.6 -0.294126912,53.3109568038,609.6 -0.2933878914,53.314354709,609.6 -0.2932361169,53.3177801097,609.6 -0.2936733382,53.3211966981,609.6 -0.2946950599,53.3245682512,609.6 -0.2962905833,53.3278590148,609.6 -0.2984431148,53.3310340837,609.6 -0.301129938,53.3340597721,609.6 -0.3043226511,53.3369039724,609.6 -0.3079874638,53.3395364964,609.6 -0.3120855537,53.3419293974,609.6 -0.3165734767,53.3440572683,609.6 -0.3214036274,53.3458975123,609.6 -0.3265247454,53.3474305843,609.6 -0.331882461,53.3486401997,609.6 -0.337419875,53.3495135088,609.6 -0.3430781667,53.3500412334,609.6 -0.3487972222,53.3502177668,609.6 + + + + + + EGRU322B WICKENBY RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8112" txt_name="WICKENBY RWY 03"><tr><td>531620N 0002232W -<br/>531634N 0002321W -<br/>531720N 0002245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to<br/>531707N 0002156W -<br/>531620N 0002232W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3756833333,53.2722333333,609.6 -0.3654925278,53.2851925278,609.6 -0.3702002326,53.2862230041,609.6 -0.374734012,53.2875034333,609.6 -0.379057,53.2890234167,609.6 -0.3892416667,53.2760666667,609.6 -0.3756833333,53.2722333333,609.6 + + + + + + EGRU322C WICKENBY RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7924" txt_name="WICKENBY RWY 21"><tr><td>532142N 0001919W -<br/>532128N 0001830W -<br/>532041N 0001907W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to<br/>532055N 0001955W -<br/>532142N 0001919W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3218611111,53.361625,609.6 -0.3320773056,53.3486772222,609.6 -0.32736351,53.3476452269,609.6 -0.3228246477,53.3463629732,609.6 -0.31849775,53.3448409167,609.6 -0.308275,53.3577916667,609.6 -0.3218611111,53.361625,609.6 + + + + + + EGRU322D WICKENBY RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="8008" txt_name="WICKENBY RWY 15"><tr><td>532121N 0002345W -<br/>532137N 0002258W -<br/>532051N 0002214W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to<br/>532035N 0002300W -<br/>532121N 0002345W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3958777778,53.3559444444,609.6 -0.3834495556,53.3429619167,609.6 -0.3793878275,53.3447268267,609.6 -0.3750764222,53.3462652363,609.6 -0.3705505,53.3475645833,609.6 -0.3828388889,53.3604055556,609.6 -0.3958777778,53.3559444444,609.6 + + + + + + EGRU322E WICKENBY RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7996" txt_name="WICKENBY RWY 33"><tr><td>531643N 0001817W -<br/>531627N 0001904W -<br/>531709N 0001944W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to<br/>531725N 0001857W -<br/>531643N 0001817W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3046611111,53.2785583333,609.6 -0.3157443333,53.2901840278,609.6 -0.3199044072,53.2885084906,609.6 -0.3242993329,53.2870643575,609.6 -0.3288933611,53.2858633611,609.6 -0.3176722222,53.2740972222,609.6 -0.3046611111,53.2785583333,609.6 + + + + + + EGRU323A CONINGSBY + <table border="1" cellpadding="1" cellspacing="0" row_id="7950" txt_name="CONINGSBY"><tr><td>A circle, 2.5 NM radius, centred at 530535N 0000958W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.1661111111,53.1346591682,609.6 -0.1724940855,53.1344815242,609.6 -0.1788224458,53.1339501119,609.6 -0.1850420493,53.1330694782,609.6 -0.1910996917,53.1318471572,609.6 -0.1969435658,53.1302936057,609.6 -0.2025237078,53.1284221129,609.6 -0.2077924272,53.1262486856,609.6 -0.2127047167,53.1237919106,609.6 -0.2172186375,53.1210727944,609.6 -0.2212956789,53.1181145826,609.6 -0.2249010863,53.1149425597,609.6 -0.2280041568,53.111583832,609.6 -0.230578499,53.108067095,609.6 -0.2326022559,53.1044223867,609.6 -0.2340582872,53.1006808309,609.6 -0.2349343111,53.0968743699,609.6 -0.2352230051,53.0930354918,609.6 -0.2349220625,53.0891969529,609.6 -0.234034207,53.0853914977,609.6 -0.2325671642,53.0816515802,609.6 -0.2305335908,53.0780090869,609.6 -0.2279509613,53.0744950661,609.6 -0.2248414152,53.0711394634,609.6 -0.2212315641,53.0679708678,609.6 -0.2171522623,53.0650162689,609.6 -0.2126383414,53.0623008282,609.6 -0.2077283123,53.0598476661,609.6 -0.2024640366,53.0576776661,609.6 -0.1968903703,53.0558092983,609.6 -0.1910547834,53.054258463,609.6 -0.1850069576,53.053038357,609.6 -0.1787983656,53.0521593616,609.6 -0.1724818368,53.0516289552,609.6 -0.1661111111,53.0514516503,609.6 -0.1597403854,53.0516289552,609.6 -0.1534238567,53.0521593616,609.6 -0.1472152647,53.053038357,609.6 -0.1411674388,53.054258463,609.6 -0.1353318519,53.0558092983,609.6 -0.1297581856,53.0576776661,609.6 -0.1244939099,53.0598476661,609.6 -0.1195838808,53.0623008282,609.6 -0.1150699599,53.0650162689,609.6 -0.1109906581,53.0679708678,609.6 -0.1073808071,53.0711394634,609.6 -0.1042712609,53.0744950661,609.6 -0.1016886314,53.0780090869,609.6 -0.099655058,53.0816515802,609.6 -0.0981880153,53.0853914977,609.6 -0.0973001597,53.0891969529,609.6 -0.0969992171,53.0930354918,609.6 -0.0972879111,53.0968743699,609.6 -0.0981639351,53.1006808309,609.6 -0.0996199663,53.1044223867,609.6 -0.1016437232,53.108067095,609.6 -0.1042180655,53.111583832,609.6 -0.1073211359,53.1149425597,609.6 -0.1109265433,53.1181145826,609.6 -0.1150035847,53.1210727944,609.6 -0.1195175056,53.1237919106,609.6 -0.124429795,53.1262486856,609.6 -0.1296985144,53.1284221129,609.6 -0.1352786564,53.1302936057,609.6 -0.1411225305,53.1318471572,609.6 -0.1471801729,53.1330694782,609.6 -0.1533997764,53.1339501119,609.6 -0.1597281367,53.1344815242,609.6 -0.1661111111,53.1346591682,609.6 + + + + + + EGRU323B CONINGSBY RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7572" txt_name="CONINGSBY RWY 07"><tr><td>530416N 0001515W -<br/>530447N 0001532W -<br/>530505N 0001402W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to<br/>530434N 0001345W -<br/>530416N 0001515W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.2541946667,53.0711036389,609.6 -0.2291673333,53.0760418333,609.6 -0.2310417153,53.0788218642,609.6 -0.2325787151,53.0816759933,609.6 -0.2337702778,53.0845893889,609.6 -0.2588251667,53.0796456944,609.6 -0.2541946667,53.0711036389,609.6 + + + + + + EGRU323C CONINGSBY RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7943" txt_name="CONINGSBY RWY 25"><tr><td>530655N 0000441W -<br/>530624N 0000424W -<br/>530606N 0000555W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to<br/>530637N 0000611W -<br/>530655N 0000441W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.0779853056,53.1151844722,609.6 -0.1031692778,53.11025525,609.6 -0.1012750652,53.1074797611,609.6 -0.0997184131,53.104629315,609.6 -0.0985073611,53.10171875,609.6 -0.0733509722,53.1066424722,609.6 -0.0779853056,53.1151844722,609.6 + + + + + + EGRU324A MONA + <table border="1" cellpadding="1" cellspacing="0" row_id="7865" txt_name="MONA"><tr><td>A circle, 2 NM radius, centred at 531533N 0042226W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.3740111111,53.2925819792,609.6 -4.3797224662,53.2924054444,609.6 -4.3853731395,53.2918777155,609.6 -4.3909030984,53.2910043994,609.6 -4.3962536017,53.289794774,609.6 -4.4013678271,53.2882616893,609.6 -4.4061914781,53.28642143,609.6 -4.4106733634,53.2842935411,609.6 -4.4147659418,53.2819006196,609.6 -4.4184258276,53.2792680728,609.6 -4.4216142504,53.2764238474,609.6 -4.4242974655,53.2733981319,609.6 -4.4264471089,53.2702230341,609.6 -4.4280404944,53.2669322399,609.6 -4.4290608507,53.2635606551,609.6 -4.4294974932,53.2601440339,609.6 -4.4293459322,53.2567185997,609.6 -4.4286079143,53.2533206608,609.6 -4.4272913986,53.2499862254,609.6 -4.4254104656,53.2467506206,609.6 -4.4229851635,53.2436481187,609.6 -4.4200412909,53.2407115749,609.6 -4.416610119,53.2379720803,609.6 -4.4127280581,53.2354586342,609.6 -4.4084362697,53.2331978382,609.6 -4.4037802294,53.2312136158,609.6 -4.3988092463,53.229526961,609.6 -4.3935759418,53.2281557169,609.6 -4.388135695,53.2271143885,609.6 -4.3825460595,53.2264139899,609.6 -4.3768661586,53.226061929,609.6 -4.3711560636,53.226061929,609.6 -4.3654761627,53.2264139899,609.6 -4.3598865272,53.2271143885,609.6 -4.3544462804,53.2281557169,609.6 -4.3492129759,53.229526961,609.6 -4.3442419928,53.2312136158,609.6 -4.3395859526,53.2331978382,609.6 -4.3352941641,53.2354586342,609.6 -4.3314121032,53.2379720803,609.6 -4.3279809314,53.2407115749,609.6 -4.3250370587,53.2436481187,609.6 -4.3226117567,53.2467506206,609.6 -4.3207308237,53.2499862254,609.6 -4.3194143079,53.2533206608,609.6 -4.3186762901,53.2567185997,609.6 -4.318524729,53.2601440339,609.6 -4.3189613715,53.2635606551,609.6 -4.3199817278,53.2669322399,609.6 -4.3215751134,53.2702230341,609.6 -4.3237247567,53.2733981319,609.6 -4.3264079718,53.2764238474,609.6 -4.3295963947,53.2792680728,609.6 -4.3332562804,53.2819006196,609.6 -4.3373488588,53.2842935411,609.6 -4.3418307441,53.28642143,609.6 -4.3466543951,53.2882616893,609.6 -4.3517686205,53.289794774,609.6 -4.3571191238,53.2910043994,609.6 -4.3626490828,53.2918777155,609.6 -4.3682997561,53.2924054444,609.6 -4.3740111111,53.2925819792,609.6 + + + + + + EGRU324B MONA RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="8018" txt_name="MONA RWY 04"><tr><td>531255N 0042513W -<br/>531315N 0042556W -<br/>531409N 0042448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to<br/>531349N 0042405W -<br/>531255N 0042513W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4203648889,53.2153488889,609.6 -4.40135675,53.2303406667,609.6 -4.4055967384,53.2319366862,609.6 -4.4095800249,53.2337554082,609.6 -4.4132741944,53.2357820556,609.6 -4.4322736944,53.2207938056,609.6 -4.4203648889,53.2153488889,609.6 + + + + + + EGRU324C MONA RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7658" txt_name="MONA RWY 22"><tr><td>531813N 0041938W -<br/>531753N 0041855W -<br/>531658N 0042005W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to<br/>531718N 0042048W -<br/>531813N 0041938W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.3271375,53.3035637222,609.6 -4.34662625,53.2882521389,609.6 -4.3423830117,53.2866539207,609.6 -4.3383978058,53.2848328586,609.6 -4.3347031111,53.2828038056,609.6 -4.3152056667,53.2981188889,609.6 -4.3271375,53.3035637222,609.6 + + + + + + EGRU325 HMP ALTCOURSE + <table border="1" cellpadding="1" cellspacing="0" row_id="14113" txt_name="HMP ALTCOURSE"><tr><td>532802N 0025617W -<br/>532801N 0025600W -<br/>532751N 0025537W -<br/>532734N 0025532W -<br/>532725N 0025547W -<br/>532726N 0025636W -<br/>532740N 0025641W -<br/>532753N 0025641W -<br/>532802N 0025617W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 86 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.93805,53.4670833333,152.4 -2.9446055556,53.4648444444,152.4 -2.9447194444,53.4612333333,152.4 -2.9432222222,53.4572638889,152.4 -2.9298333333,53.4570138889,152.4 -2.9254722222,53.4595444444,152.4 -2.9268444444,53.4641,152.4 -2.9333222222,53.46705,152.4 -2.93805,53.4670833333,152.4 + + + + + + EGRU326 HMP ASKHAM GRANGE + <table border="1" cellpadding="1" cellspacing="0" row_id="14149" txt_name="HMP ASKHAM GRANGE"><tr><td>535551N 0011124W -<br/>535552N 0011041W -<br/>535537N 0011031W -<br/>535520N 0011046W -<br/>535516N 0011105W -<br/>535520N 0011123W -<br/>535539N 0011137W -<br/>535551N 0011124W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 104 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1900611111,53.9308583333,182.88 -1.1936361111,53.9275305556,182.88 -1.1895888889,53.9222666667,182.88 -1.1848388889,53.9211972222,182.88 -1.1794583333,53.9221,182.88 -1.1751583333,53.9269861111,182.88 -1.1780777778,53.9311083333,182.88 -1.1900611111,53.9308583333,182.88 + + + + + + EGRU327 HMP BERWYN + <table border="1" cellpadding="1" cellspacing="0" row_id="14081" txt_name="HMP BERWYN"><tr><td>530233N 0025539W -<br/>530210N 0025453W -<br/>530137N 0025537W -<br/>530159N 0025625W -<br/>530233N 0025539W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 118 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.927375,53.0424444444,182.88 -2.9403833333,53.0330111111,182.88 -2.9270166667,53.0268944444,182.88 -2.9147805556,53.0362027778,182.88 -2.927375,53.0424444444,182.88 + + + + + + EGRU328 HMP BUCKLEY HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14106" txt_name="HMP BUCKLEY HALL"><tr><td>533825N 0020916W -<br/>533826N 0020823W -<br/>533805N 0020814W -<br/>533754N 0020816W -<br/>533744N 0020841W -<br/>533758N 0020909W -<br/>533825N 0020916W <br/>Upper limit: 1000 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 585 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.154525,53.6402944444,304.8 -2.1525222222,53.6327444444,304.8 -2.1448333333,53.6288722222,304.8 -2.1377555556,53.6317027778,304.8 -2.1370972222,53.6348333333,304.8 -2.1397833333,53.6406194444,304.8 -2.154525,53.6402944444,304.8 + + + + + + EGRU329 HMP DONCASTER + <table border="1" cellpadding="1" cellspacing="0" row_id="14097" txt_name="HMP DONCASTER"><tr><td>533154N 0010840W -<br/>533130N 0010807W -<br/>533104N 0010843W -<br/>533126N 0010928W -<br/>533154N 0010840W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 55 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.1444388889,53.5315583333,152.4 -1.1577666667,53.5239944444,152.4 -1.1453638889,53.5177194444,152.4 -1.1354083333,53.5251083333,152.4 -1.1444388889,53.5315583333,152.4 + + + + + + EGRU330 HMP FOREST BANK + <table border="1" cellpadding="1" cellspacing="0" row_id="14087" txt_name="HMP FOREST BANK"><tr><td>533113N 0021811W -<br/>533102N 0021732W -<br/>533047N 0021730W -<br/>533029N 0021808W -<br/>533056N 0021847W -<br/>533113N 0021811W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 128 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.3030138889,53.5202,182.88 -2.3129333333,53.5156833333,182.88 -2.3022722222,53.5080277778,182.88 -2.2917777778,53.5130083333,182.88 -2.2921805556,53.5171638889,182.88 -2.3030138889,53.5202,182.88 + + + + + + EGRU331 HMP FULL SUTTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14129" txt_name="HMP FULL SUTTON"><tr><td>535923N 0005234W -<br/>535920N 0005134W -<br/>535842N 0005138W -<br/>535845N 0005239W -<br/>535923N 0005234W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 57 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.8760472222,53.9896138889,152.4 -0.8775861111,53.979075,152.4 -0.8606055556,53.9782,152.4 -0.8593111111,53.9888222222,152.4 -0.8760472222,53.9896138889,152.4 + + + + + + EGRU332 HMP GARTH/WYMOTT + <table border="1" cellpadding="1" cellspacing="0" row_id="14111" txt_name="HMP GARTH/WYMOTT"><tr><td>534108N 0024604W -<br/>534108N 0024455W -<br/>534103N 0024428W -<br/>534023N 0024424W -<br/>534022N 0024529W -<br/>534033N 0024603W -<br/>534108N 0024604W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 50 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7676833333,53.6854666667,152.4 -2.7675444444,53.6757666667,152.4 -2.7581694444,53.6728833333,152.4 -2.7399944444,53.6731444444,152.4 -2.7410666667,53.6841611111,152.4 -2.7487361111,53.6856027778,152.4 -2.7676833333,53.6854666667,152.4 + + + + + + EGRU333 HMP HINDLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14110" txt_name="HMP HINDLEY"><tr><td>533127N 0023410W -<br/>533057N 0023356W -<br/>533048N 0023459W -<br/>533119N 0023510W -<br/>533127N 0023410W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 127 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5694444444,53.5242805556,182.88 -2.5862361111,53.5218611111,182.88 -2.5829361111,53.5132916667,182.88 -2.5656388889,53.5157472222,182.88 -2.5694444444,53.5242805556,182.88 + + + + + + EGRU334 HMP HULL + <table border="1" cellpadding="1" cellspacing="0" row_id="14075" txt_name="HMP HULL"><tr><td>534518N 0001815W -<br/>534518N 0001708W -<br/>534458N 0001709W -<br/>534439N 0001732W -<br/>534439N 0001817W -<br/>534518N 0001815W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 17 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.3041611111,53.7549277778,152.4 -0.3046055556,53.7440388889,152.4 -0.2920833333,53.74415,152.4 -0.2857472222,53.7494888889,152.4 -0.2854222222,53.7550638889,152.4 -0.3041611111,53.7549277778,152.4 + + + + + + EGRU335 HMP HUMBER + <table border="1" cellpadding="1" cellspacing="0" row_id="14138" txt_name="HMP HUMBER"><tr><td>534633N 0003818W -<br/>534627N 0003753W -<br/>534605N 0003727W -<br/>534549N 0003759W -<br/>534550N 0003846W -<br/>534617N 0003904W -<br/>534633N 0003818W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 71 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6382388889,53.7757222222,152.4 -0.6510861111,53.7714277778,152.4 -0.6461416667,53.7639166667,152.4 -0.6329944444,53.7635388889,152.4 -0.6240388889,53.7680166667,152.4 -0.6313444444,53.7741194444,152.4 -0.6382388889,53.7757222222,152.4 + + + + + + EGRU336 HMP LEEDS + <table border="1" cellpadding="1" cellspacing="0" row_id="14120" txt_name="HMP LEEDS"><tr><td>534805N 0013438W -<br/>534758N 0013410W -<br/>534733N 0013407W -<br/>534727N 0013438W -<br/>534739N 0013509W -<br/>534801N 0013501W -<br/>534805N 0013438W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 245 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5773277778,53.8012805556,213.36 -1.5836694444,53.8002944444,213.36 -1.5858305556,53.7941166667,213.36 -1.5771444444,53.7907694444,213.36 -1.5686861111,53.7924361111,213.36 -1.5694972222,53.7994833333,213.36 -1.5773277778,53.8012805556,213.36 + + + + + + EGRU337 HMP LINCOLN + <table border="1" cellpadding="1" cellspacing="0" row_id="14078" txt_name="HMP LINCOLN"><tr><td>531426N 0003115W -<br/>531422N 0003038W -<br/>531400N 0003032W -<br/>531350N 0003046W -<br/>531353N 0003122W -<br/>531401N 0003132W -<br/>531415N 0003132W -<br/>531426N 0003115W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Restricted Area (EGR313) Waddington and HMPPS.<br/>Contact: RAF Waddington Station Ops 01522-726532 or email: wad-stationops@mod.gov.uk<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 163 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.5207194444,53.24055,182.88 -0.5256916667,53.2375583333,182.88 -0.5254333333,53.2337277778,182.88 -0.5227,53.2314527778,182.88 -0.5127777778,53.2306444444,182.88 -0.5089916667,53.2332305556,182.88 -0.5106,53.2393777778,182.88 -0.5207194444,53.24055,182.88 + + + + + + EGRU338 HMP LINDHOLME/MOORLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="14096" txt_name="HMP LINDHOLME/MOORLAND"><tr><td>533313N 0005850W -<br/>533311N 0005732W -<br/>533254N 0005713W -<br/>533214N 0005733W -<br/>533219N 0005853W -<br/>533313N 0005850W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 29 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9806055556,53.5535833333,152.4 -0.9814833333,53.5387166667,152.4 -0.9591083333,53.5372694444,152.4 -0.9536722222,53.5484222222,152.4 -0.9588222222,53.5530611111,152.4 -0.9806055556,53.5535833333,152.4 + + + + + + EGRU339 HMP LIVERPOOL + <table border="1" cellpadding="1" cellspacing="0" row_id="14077" txt_name="HMP LIVERPOOL"><tr><td>532740N 0025848W -<br/>532750N 0025753W -<br/>532742N 0025741W -<br/>532719N 0025731W -<br/>532706N 0025834W -<br/>532740N 0025848W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 117 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9800194444,53.4611777778,182.88 -2.9762333333,53.4516722222,182.88 -2.9585833333,53.4552138889,182.88 -2.9614138889,53.4616583333,182.88 -2.9647527778,53.4638861111,182.88 -2.9800194444,53.4611777778,182.88 + + + + + + EGRU340 HMP LOWDHAM GRANGE + <table border="1" cellpadding="1" cellspacing="0" row_id="14088" txt_name="HMP LOWDHAM GRANGE"><tr><td>530115N 0010219W -<br/>530110N 0010156W -<br/>530055N 0010149W -<br/>530039N 0010203W -<br/>530035N 0010234W -<br/>530052N 0010258W -<br/>530108N 0010247W -<br/>530115N 0010219W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 281 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.0387222222,53.0207638889,213.36 -1.04635,53.0188944444,213.36 -1.0495444444,53.0145166667,213.36 -1.0426388889,53.0096305556,213.36 -1.0340305556,53.010775,213.36 -1.0301833333,53.0151972222,213.36 -1.0323027778,53.019425,213.36 -1.0387222222,53.0207638889,213.36 + + + + + + EGRU341 HMP MANCHESTER + <table border="1" cellpadding="1" cellspacing="0" row_id="14089" txt_name="HMP MANCHESTER"><tr><td>533000N 0021509W -<br/>532957N 0021446W -<br/>532943N 0021414W -<br/>532929N 0021413W -<br/>532919N 0021435W -<br/>532916N 0021448W -<br/>532920N 0021507W -<br/>532937N 0021520W -<br/>533000N 0021509W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 153 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2525083333,53.5000555556,182.88 -2.2556861111,53.4935416667,182.88 -2.2519944444,53.4887888889,182.88 -2.2465805556,53.4877444444,182.88 -2.242975,53.4886138889,182.88 -2.2370361111,53.4915083333,182.88 -2.2373111111,53.4954055556,182.88 -2.246225,53.4992083333,182.88 -2.2525083333,53.5000555556,182.88 + + + + + + EGRU342 HMP MORTON HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14080" txt_name="HMP MORTON HALL"><tr><td>531026N 0004128W -<br/>531021N 0004043W -<br/>530946N 0004034W -<br/>530938N 0004054W -<br/>530942N 0004135W -<br/>531008N 0004144W -<br/>531026N 0004128W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 79 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.6910888889,53.1738,152.4 -0.6956666667,53.1687666667,152.4 -0.6930166667,53.1615611111,152.4 -0.6816,53.1605805556,152.4 -0.6761861111,53.1627138889,152.4 -0.6785611111,53.1725222222,152.4 -0.6910888889,53.1738,152.4 + + + + + + EGRU343 HMP NEW HALL + <table border="1" cellpadding="1" cellspacing="0" row_id="14121" txt_name="HMP NEW HALL"><tr><td>533826N 0013700W -<br/>533826N 0013620W -<br/>533811N 0013613W -<br/>533753N 0013618W -<br/>533752N 0013640W -<br/>533800N 0013716W -<br/>533818N 0013719W -<br/>533826N 0013700W <br/>Upper limit: 900 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 458 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6165638889,53.6405861111,274.32 -1.6218666667,53.6384694444,274.32 -1.6211555556,53.6332194444,274.32 -1.6110805556,53.6311361111,274.32 -1.6048611111,53.6312833333,274.32 -1.6036416667,53.6364944444,274.32 -1.6056888889,53.6405777778,274.32 -1.6165638889,53.6405861111,274.32 + + + + + + EGRU344 HMP PRESTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14085" txt_name="HMP PRESTON"><tr><td>534606N 0024105W -<br/>534537N 0024043W -<br/>534525N 0024124W -<br/>534538N 0024149W -<br/>534555N 0024139W -<br/>534606N 0024105W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 147 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6846,53.7683555556,182.88 -2.6940861111,53.7653888889,182.88 -2.6968777778,53.7606694444,182.88 -2.6900666667,53.7569972222,182.88 -2.6785833333,53.760175,182.88 -2.6846,53.7683555556,182.88 + + + + + + EGRU345 HMP RANBY + <table border="1" cellpadding="1" cellspacing="0" row_id="14140" txt_name="HMP RANBY"><tr><td>531943N 0005946W -<br/>531922N 0005920W -<br/>531858N 0005925W -<br/>531903N 0010035W -<br/>531926N 0010034W -<br/>531943N 0005946W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 153 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-0.9960666667,53.3286666667,182.88 -1.009525,53.3238277778,182.88 -1.0096972222,53.3174138889,182.88 -0.9902694444,53.3160194444,182.88 -0.9887527778,53.3227777778,182.88 -0.9960666667,53.3286666667,182.88 + + + + + + EGRU346 HMP RISLEY + <table border="1" cellpadding="1" cellspacing="0" row_id="14135" txt_name="HMP RISLEY"><tr><td>532638N 0023135W -<br/>532635N 0023109W -<br/>532624N 0023059W -<br/>532602N 0023050W -<br/>532558N 0023204W -<br/>532625N 0023154W -<br/>532638N 0023135W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 126 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.5262638889,53.4438638889,182.88 -2.5317916667,53.4401555556,182.88 -2.5344305556,53.4327611111,182.88 -2.5137916667,53.4338666667,182.88 -2.5162555556,53.4399416667,182.88 -2.5190416667,53.443075,182.88 -2.5262638889,53.4438638889,182.88 + + + + + + EGRU347 HMP STYAL + <table border="1" cellpadding="1" cellspacing="0" row_id="14133" txt_name="HMP STYAL"><tr><td>532043N 0021412W -<br/>532031N 0021342W -<br/>532010N 0021357W -<br/>532005N 0021442W -<br/>532019N 0021500W -<br/>532038N 0021441W -<br/>532043N 0021412W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.<br/>NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 271 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2365972222,53.3452222222,213.36 -2.2448416667,53.3438305556,213.36 -2.2500166667,53.3386916667,213.36 -2.2451083333,53.3347666667,213.36 -2.2324833333,53.3360222222,213.36 -2.2282388889,53.3418388889,213.36 -2.2365972222,53.3452222222,213.36 + + + + + + EGRU348 HMP WAKEFIELD + <table border="1" cellpadding="1" cellspacing="0" row_id="14154" txt_name="HMP WAKEFIELD"><tr><td>534112N 0013105W -<br/>534118N 0013027W -<br/>534051N 0012947W -<br/>534035N 0013042W -<br/>534054N 0013104W -<br/>534112N 0013105W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 117 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5180833333,53.6866277778,182.88 -1.5176888889,53.6818027778,182.88 -1.511725,53.67625,182.88 -1.4965,53.6807305556,182.88 -1.5075333333,53.6883444444,182.88 -1.5180833333,53.6866277778,182.88 + + + + + + EGRU349 HMP WEALSTUN + <table border="1" cellpadding="1" cellspacing="0" row_id="14150" txt_name="HMP WEALSTUN"><tr><td>535520N 0011957W -<br/>535515N 0011917W -<br/>535456N 0011909W -<br/>535432N 0011932W -<br/>535432N 0011955W -<br/>535443N 0012021W -<br/>535454N 0012018W -<br/>535506N 0012011W -<br/>535520N 0011957W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 104 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.33255,53.9221611111,182.88 -1.3364861111,53.9183027778,182.88 -1.3382055556,53.9151166667,182.88 -1.3392722222,53.9119583333,182.88 -1.3319944444,53.9089,182.88 -1.3256611111,53.9087638889,182.88 -1.3190305556,53.9155222222,182.88 -1.3214888889,53.9207194444,182.88 -1.33255,53.9221611111,182.88 + + + + + + EGRU350 HMP WERRINGTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14092" txt_name="HMP WERRINGTON"><tr><td>530135N 0020538W -<br/>530140N 0020507W -<br/>530131N 0020450W -<br/>530108N 0020437W -<br/>530100N 0020530W -<br/>530118N 0020540W -<br/>530135N 0020538W <br/>Upper limit: 1300 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 834 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.0938416667,53.0264583333,396.24 -2.094375,53.0216055556,396.24 -2.0916583333,53.0165722222,396.24 -2.0768916667,53.0187611111,396.24 -2.0805333333,53.0252555556,396.24 -2.0854083333,53.0276388889,396.24 -2.0938416667,53.0264583333,396.24 + + + + + + EGRU351 HMP WETHERBY + <table border="1" cellpadding="1" cellspacing="0" row_id="14131" txt_name="HMP WETHERBY"><tr><td>535628N 0012218W -<br/>535633N 0012138W -<br/>535557N 0012124W -<br/>535551N 0012229W -<br/>535616N 0012241W -<br/>535623N 0012221W -<br/>535628N 0012218W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 89 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3716555556,53.9410944444,152.4 -1.3724861111,53.9397888889,152.4 -1.3780666667,53.9377611111,152.4 -1.3747638889,53.9308861111,152.4 -1.3567138889,53.9324555556,152.4 -1.3605833333,53.9424916667,152.4 -1.3716555556,53.9410944444,152.4 + + + + + + EGRU401A ENNISKILLEN/ST ANGELO + <table border="1" cellpadding="1" cellspacing="0" row_id="7599" txt_name="ENNISKILLEN/ST ANGELO"><tr><td>A circle, 2 NM radius, centred at 542355N 0073907W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.6518944444,54.4319645097,609.6 -7.6577631133,54.4317880028,609.6 -7.6635694228,54.4312603575,609.6 -7.6692516811,54.4303871803,609.6 -7.6747495237,54.4291777486,609.6 -7.680004559,54.4276449115,609.6 -7.6849609919,54.4258049525,609.6 -7.6895662193,54.423677415,609.6 -7.6937713903,54.4212848941,609.6 -7.6975319255,54.4186527945,609.6 -7.7008079893,54.4158090603,609.6 -7.7035649119,54.4127838759,609.6 -7.7057735534,54.4096093453,609.6 -7.7074106097,54.4063191496,609.6 -7.7084588548,54.4029481892,609.6 -7.7089073179,54.3995322122,609.6 -7.7087513939,54.3961074356,609.6 -7.7079928858,54.3927101604,609.6 -7.7066399793,54.3893763876,609.6 -7.7047071497,54.3861414363,609.6 -7.7022150032,54.3830395707,609.6 -7.6991900532,54.380103638,609.6 -7.6956644351,54.3773647213,609.6 -7.691675563,54.3748518119,609.6 -7.6872657315,54.372591504,609.6 -7.6824816662,54.3706077142,609.6 -7.6773740298,54.3689214302,609.6 -7.6719968874,54.3675504896,609.6 -7.6664071357,54.366509393,609.6 -7.6606639053,54.3658091509,609.6 -7.6548279383,54.3654571688,609.6 -7.6489609506,54.3654571688,609.6 -7.6431249836,54.3658091509,609.6 -7.6373817532,54.366509393,609.6 -7.6317920015,54.3675504896,609.6 -7.626414859,54.3689214302,609.6 -7.6213072227,54.3706077142,609.6 -7.6165231574,54.372591504,609.6 -7.6121133258,54.3748518119,609.6 -7.6081244538,54.3773647213,609.6 -7.6045988357,54.380103638,609.6 -7.6015738857,54.3830395707,609.6 -7.5990817392,54.3861414363,609.6 -7.5971489096,54.3893763876,609.6 -7.595796003,54.3927101604,609.6 -7.5950374949,54.3961074356,609.6 -7.594881571,54.3995322122,609.6 -7.5953300341,54.4029481892,609.6 -7.5963782792,54.4063191496,609.6 -7.5980153355,54.4096093453,609.6 -7.600223977,54.4127838759,609.6 -7.6029808996,54.4158090603,609.6 -7.6062569634,54.4186527945,609.6 -7.6100174985,54.4212848941,609.6 -7.6142226696,54.423677415,609.6 -7.618827897,54.4258049525,609.6 -7.6237843299,54.4276449115,609.6 -7.6290393652,54.4291777486,609.6 -7.6345372078,54.4303871803,609.6 -7.6402194661,54.4312603575,609.6 -7.6460257756,54.4317880028,609.6 -7.6518944444,54.4319645097,609.6 + + + + + + EGRU401B ENNISKILLEN/ST ANGELO RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="8103" txt_name="ENNISKILLEN/ST ANGELO RWY 14"><tr><td>542602N 0074247W -<br/>542623N 0074205W -<br/>542536N 0074057W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to<br/>542515N 0074139W -<br/>542602N 0074247W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.7130888889,54.4338694444,609.6 -7.694273,54.4209643056,609.6 -7.6906578306,54.4231026591,609.6 -7.6867264144,54.4250421238,609.6 -7.6825108056,54.4267668889,609.6 -7.7013388889,54.4396833333,609.6 -7.7130888889,54.4338694444,609.6 + + + + + + EGRU401C ENNISKILLEN/ST ANGELO RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="8120" txt_name="ENNISKILLEN/ST ANGELO RWY 32"><tr><td>542152N 0073531W -<br/>542131N 0073613W -<br/>542214N 0073716W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to<br/>542235N 0073634W -<br/>542152N 0073531W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5918305556,54.3644027778,609.6 -7.6093981667,54.3765048056,609.6 -7.61299728,54.3743600838,609.6 -7.6169125119,54.3724133666,609.6 -7.621112,54.3706804722,609.6 -7.6035555556,54.3585888889,609.6 -7.5918305556,54.3644027778,609.6 + + + + + + EGRU402A BELFAST ALDERGROVE + <table border="1" cellpadding="1" cellspacing="0" row_id="7983" txt_name="BELFAST ALDERGROVE"><tr><td>A circle, 2.5 NM radius, centred at 543927N 0061257W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2158333333,54.6990927064,609.6 -6.2224594592,54.6989150989,609.6 -6.229028881,54.698383796,609.6 -6.2354853842,54.6975033443,609.6 -6.2417737294,54.6962812779,609.6 -6.2478401287,54.6947280529,609.6 -6.2536327092,54.6928569577,609.6 -6.2591019599,54.6906839982,609.6 -6.2642011568,54.6882277598,609.6 -6.2688867638,54.6855092472,609.6 -6.2731188056,54.6825517036,609.6 -6.2768612078,54.6793804105,609.6 -6.2800821046,54.6760224706,609.6 -6.2827541076,54.672506575,609.6 -6.2848545372,54.6688627568,609.6 -6.2863656112,54.6651221334,609.6 -6.2872745925,54.6613166408,609.6 -6.2875738922,54.6574787594,609.6 -6.2872611287,54.6536412373,609.6 -6.286339142,54.6498368101,609.6 -6.2848159641,54.6460979221,609.6 -6.2827047442,54.6424564499,609.6 -6.2800236317,54.6389434314,609.6 -6.2767956168,54.6355888016,609.6 -6.27304833,54.6324211387,609.6 -6.2688138037,54.6294674219,609.6 -6.2641281966,54.6267528025,609.6 -6.2590314843,54.6243003909,609.6 -6.2535671181,54.6221310617,609.6 -6.2477816558,54.6202632766,609.6 -6.2417243659,54.6187129286,609.6 -6.2354468111,54.6174932083,609.6 -6.2290024118,54.616614492,609.6 -6.2224459954,54.6160842545,609.6 -6.2158333333,54.6159070062,609.6 -6.2092206713,54.6160842545,609.6 -6.2026642549,54.616614492,609.6 -6.1962198556,54.6174932083,609.6 -6.1899423008,54.6187129286,609.6 -6.1838850109,54.6202632766,609.6 -6.1780995485,54.6221310617,609.6 -6.1726351824,54.6243003909,609.6 -6.1675384701,54.6267528025,609.6 -6.162852863,54.6294674219,609.6 -6.1586183367,54.6324211387,609.6 -6.1548710499,54.6355888016,609.6 -6.151643035,54.6389434314,609.6 -6.1489619225,54.6424564499,609.6 -6.1468507026,54.6460979221,609.6 -6.1453275246,54.6498368101,609.6 -6.144405538,54.6536412373,609.6 -6.1440927744,54.6574787594,609.6 -6.1443920742,54.6613166408,609.6 -6.1453010555,54.6651221334,609.6 -6.1468121295,54.6688627568,609.6 -6.148912559,54.672506575,609.6 -6.1515845621,54.6760224706,609.6 -6.1548054589,54.6793804105,609.6 -6.1585478611,54.6825517036,609.6 -6.1627799028,54.6855092472,609.6 -6.1674655099,54.6882277598,609.6 -6.1725647068,54.6906839982,609.6 -6.1780339574,54.6928569577,609.6 -6.183826538,54.6947280529,609.6 -6.1898929372,54.6962812779,609.6 -6.1961812825,54.6975033443,609.6 -6.2026377857,54.698383796,609.6 -6.2092072075,54.6989150989,609.6 -6.2158333333,54.6990927064,609.6 + + + + + + EGRU402B BELFAST ALDERGROVE RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7834" txt_name="BELFAST ALDERGROVE RWY 07"><tr><td>543745N 0061808W -<br/>543815N 0061831W -<br/>543839N 0061702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to<br/>543810N 0061638W -<br/>543745N 0061808W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3021944444,54.6292277778,609.6 -6.2772079722,54.6359791667,609.6 -6.2797248099,54.6386001004,609.6 -6.2819096729,54.6413194151,609.6 -6.2837511667,54.6441229722,609.6 -6.3087138889,54.6373777778,609.6 -6.3021944444,54.6292277778,609.6 + + + + + + EGRU402C BELFAST ALDERGROVE RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7908" txt_name="BELFAST ALDERGROVE RWY 25"><tr><td>544109N 0060745W -<br/>544039N 0060721W -<br/>544015N 0060852W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to<br/>544044N 0060916W -<br/>544109N 0060745W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.1291305556,54.6857388889,609.6 -6.1543686389,54.6789653889,609.6 -6.1518605176,54.6763409319,609.6 -6.1496856953,54.6736184898,609.6 -6.1478554167,54.67081225,609.6 -6.1225944444,54.6775916667,609.6 -6.1291305556,54.6857388889,609.6 + + + + + + EGRU402D BELFAST ALDERGROVE RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="8019" txt_name="BELFAST ALDERGROVE RWY 17"><tr><td>544157N 0061536W -<br/>544207N 0061443W -<br/>544146N 0061431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to<br/>544131N 0061521W -<br/>544157N 0061536W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2600159167,54.6992365556,609.6 -6.2559364167,54.6919939444,609.6 -6.2514765225,54.693601312,609.6 -6.2468253619,54.6950153278,609.6 -6.2420078889,54.6962284167,609.6 -6.2452674167,54.7020187778,609.6 -6.2600159167,54.6992365556,609.6 + + + + + + EGRU402E BELFAST ALDERGROVE RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7826" txt_name="BELFAST ALDERGROVE RWY 35"><tr><td>543604N 0061119W -<br/>543554N 0061212W -<br/>543657N 0061247W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to<br/>543702N 0061152W -<br/>543604N 0061119W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.18867225,54.6012328056,609.6 -6.1976555556,54.6172657222,609.6 -6.2027725007,54.6166028186,609.6 -6.2079591337,54.6161585674,609.6 -6.2131877778,54.6159353333,609.6 -6.2033843056,54.5984505556,609.6 -6.18867225,54.6012328056,609.6 + + + + + + EGRU403A BELFAST/CITY + <table border="1" cellpadding="1" cellspacing="0" row_id="7544" txt_name="BELFAST/CITY"><tr><td>A circle, 2 NM radius, centred at 543705N 0055221W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.8725,54.6513299617,609.6 -5.8784002309,54.6511534601,609.6 -5.8842377659,54.6506258306,609.6 -5.8899505801,54.6497526798,609.6 -5.8954779834,54.6485432848,609.6 -5.9007612692,54.6470104947,609.6 -5.905744342,54.6451705926,609.6 -5.9103743152,54.6430431218,609.6 -5.9146020751,54.6406506769,609.6 -5.9183828029,54.6380186624,609.6 -5.9216764494,54.6351750215,609.6 -5.9244481591,54.6321499383,609.6 -5.9266686364,54.6289755157,609.6 -5.9283144534,54.6256854341,609.6 -5.9293682929,54.6223145928,609.6 -5.9298191266,54.6188987388,609.6 -5.9296623264,54.6154740878,609.6 -5.9288997065,54.6120769396,609.6 -5.9275394983,54.6087432935,609.6 -5.9255962562,54.6055084673,609.6 -5.9230906984,54.6024067236,609.6 -5.9200494818,54.5994709081,609.6 -5.9165049151,54.5967321021,609.6 -5.912494614,54.5942192958,609.6 -5.9080611001,54.5919590816,609.6 -5.90325135,54.5899753748,609.6 -5.898116298,54.588289162,609.6 -5.8927102986,54.5869182798,609.6 -5.8870905533,54.5858772276,609.6 -5.8813165087,54.5851770156,609.6 -5.8754492317,54.5848250486,609.6 -5.8695507683,54.5848250486,609.6 -5.8636834913,54.5851770156,609.6 -5.8579094467,54.5858772276,609.6 -5.8522897014,54.5869182798,609.6 -5.846883702,54.588289162,609.6 -5.84174865,54.5899753748,609.6 -5.8369388999,54.5919590816,609.6 -5.832505386,54.5942192958,609.6 -5.8284950849,54.5967321021,609.6 -5.8249505182,54.5994709081,609.6 -5.8219093016,54.6024067236,609.6 -5.8194037438,54.6055084673,609.6 -5.8174605017,54.6087432935,609.6 -5.8161002935,54.6120769396,609.6 -5.8153376736,54.6154740878,609.6 -5.8151808734,54.6188987388,609.6 -5.8156317071,54.6223145928,609.6 -5.8166855466,54.6256854341,609.6 -5.8183313636,54.6289755157,609.6 -5.8205518409,54.6321499383,609.6 -5.8233235506,54.6351750215,609.6 -5.8266171971,54.6380186624,609.6 -5.8303979249,54.6406506769,609.6 -5.8346256848,54.6430431218,609.6 -5.839255658,54.6451705926,609.6 -5.8442387308,54.6470104947,609.6 -5.8495220166,54.6485432848,609.6 -5.8550494199,54.6497526798,609.6 -5.8607622341,54.6506258306,609.6 -5.8665997691,54.6511534601,609.6 -5.8725,54.6513299617,609.6 + + + + + + EGRU403B BELFAST/CITY RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="8162" txt_name="BELFAST/CITY RWY 04"><tr><td>543421N 0055503W -<br/>543440N 0055549W -<br/>543537N 0055441W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to<br/>543518N 0055355W -<br/>543421N 0055503W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.9174916667,54.5725666667,609.6 -5.8985663889,54.5884211389,609.6 -5.9030612095,54.5899055038,609.6 -5.9073076397,54.5916190103,609.6 -5.9112711389,54.5935477222,609.6 -5.9301944444,54.5776916667,609.6 -5.9174916667,54.5725666667,609.6 + + + + + + EGRU403C BELFAST/CITY RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7779" txt_name="BELFAST/CITY RWY 22"><tr><td>543951N 0054936W -<br/>543933N 0054850W -<br/>543833N 0055002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to<br/>543852N 0055047W -<br/>543951N 0054936W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.8266055556,54.6643027778,609.6 -5.8464906111,54.6477122778,609.6 -5.8419875834,54.6462309714,609.6 -5.8377334708,54.6445201629,609.6 -5.8337629444,54.6425938056,609.6 -5.813875,54.6591833333,609.6 -5.8266055556,54.6643027778,609.6 + + + + + + EGRU404A NEWTOWNARDS + <table border="1" cellpadding="1" cellspacing="0" row_id="7628" txt_name="NEWTOWNARDS"><tr><td>A circle, 2 NM radius, centred at 543452N 0054131W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6919444444,54.6143857216,609.6 -5.69783933,54.6142092191,609.6 -5.7036715766,54.613681587,609.6 -5.7093792158,54.6128084317,609.6 -5.7149016127,54.6115990305,609.6 -5.720180114,54.6100662325,609.6 -5.725158675,54.6082263209,609.6 -5.7297844573,54.6060988389,609.6 -5.7340083916,54.6037063812,609.6 -5.7377856995,54.6010743524,609.6 -5.7410763683,54.5982306958,609.6 -5.7438455736,54.5952055956,609.6 -5.7460640464,54.5920311548,609.6 -5.7477083797,54.5887410541,609.6 -5.7487612717,54.5853701927,609.6 -5.749211704,54.581954318,609.6 -5.7490550522,54.5785296459,609.6 -5.7482931288,54.5751324763,609.6 -5.7469341571,54.5717988089,609.6 -5.7449926785,54.5685639616,609.6 -5.7424893921,54.5654621975,609.6 -5.7394509304,54.5625263622,609.6 -5.7359095728,54.5597875376,609.6 -5.7319029009,54.5572747139,609.6 -5.7274733979,54.5550144839,609.6 -5.7226679978,54.5530307632,609.6 -5.7175375889,54.5513445384,609.6 -5.7121364767,54.5499736463,609.6 -5.7065218111,54.5489325867,609.6 -5.7007529851,54.5482323696,609.6 -5.6948910108,54.5478804001,609.6 -5.6889978781,54.5478804001,609.6 -5.6831359038,54.5482323696,609.6 -5.6773670778,54.5489325867,609.6 -5.6717524122,54.5499736463,609.6 -5.6663513,54.5513445384,609.6 -5.6612208911,54.5530307632,609.6 -5.656415491,54.5550144839,609.6 -5.6519859879,54.5572747139,609.6 -5.6479793161,54.5597875376,609.6 -5.6444379585,54.5625263622,609.6 -5.6413994968,54.5654621975,609.6 -5.6388962103,54.5685639616,609.6 -5.6369547318,54.5717988089,609.6 -5.6355957601,54.5751324763,609.6 -5.6348338367,54.5785296459,609.6 -5.6346771849,54.581954318,609.6 -5.6351276172,54.5853701927,609.6 -5.6361805092,54.5887410541,609.6 -5.6378248425,54.5920311548,609.6 -5.6400433153,54.5952055956,609.6 -5.6428125206,54.5982306958,609.6 -5.6461031894,54.6010743524,609.6 -5.6498804973,54.6037063812,609.6 -5.6541044316,54.6060988389,609.6 -5.6587302139,54.6082263209,609.6 -5.6637087749,54.6100662325,609.6 -5.6689872762,54.6115990305,609.6 -5.6745096731,54.6128084317,609.6 -5.6802173123,54.613681587,609.6 -5.6860495589,54.6142092191,609.6 -5.6919444444,54.6143857216,609.6 + + + + + + EGRU404B NEWTOWNARDS RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8046" txt_name="NEWTOWNARDS RWY 03"><tr><td>543214N 0054343W -<br/>543231N 0054430W -<br/>543319N 0054340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543302N 0054253W -<br/>543214N 0054343W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7285722222,54.5372,609.6 -5.7146738611,54.5505698333,609.6 -5.719318224,54.5518842841,609.6 -5.7237401423,54.5534366053,609.6 -5.7279036667,54.5552141667,609.6 -5.7417916667,54.54185,609.6 -5.7285722222,54.5372,609.6 + + + + + + EGRU404C NEWTOWNARDS RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7997" txt_name="NEWTOWNARDS RWY 21"><tr><td>543727N 0053922W -<br/>543710N 0053834W -<br/>543625N 0053921W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543642N 0054009W -<br/>543727N 0053922W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6560305556,54.6242111111,609.6 -5.6691476389,54.6116395833,609.6 -5.6644993349,54.6103214286,609.6 -5.660075022,54.6087652411,609.6 -5.6559107778,54.6069837222,609.6 -5.6427833333,54.6195611111,609.6 -5.6560305556,54.6242111111,609.6 + + + + + + EGRU404D NEWTOWNARDS RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7793" txt_name="NEWTOWNARDS RWY 08"><tr><td>543356N 0054615W -<br/>543428N 0054627W -<br/>543440N 0054456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543408N 0054443W -<br/>543356N 0054615W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7707888889,54.5655638889,609.6 -5.7453074167,54.5690223611,609.6 -5.7469677702,54.5718659434,609.6 -5.7481803273,54.5747849007,609.6 -5.7489351389,54.5777554722,609.6 -5.7742916667,54.5743138889,609.6 -5.7707888889,54.5655638889,609.6 + + + + + + EGRU404E NEWTOWNARDS RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7993" txt_name="NEWTOWNARDS RWY 26"><tr><td>543545N 0053655W -<br/>543513N 0053642W -<br/>543502N 0053806W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543534N 0053818W -<br/>543545N 0053655W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6151472222,54.5958166667,609.6 -5.6382448611,54.5927102222,609.6 -5.6366648302,54.5898510472,609.6 -5.6355352653,54.5869207834,609.6 -5.6348652778,54.5839433056,609.6 -5.6116416667,54.5870666667,609.6 -5.6151472222,54.5958166667,609.6 + + + + + + EGRU404F NEWTOWNARDS RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7530" txt_name="NEWTOWNARDS RWY 15"><tr><td>543716N 0054418W -<br/>543733N 0054330W -<br/>543645N 0054241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543630N 0054331W -<br/>543716N 0054418W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7383444444,54.6211611111,609.6 -5.7251928056,54.6082122222,609.6 -5.7208435871,54.6098446568,609.6 -5.7162579728,54.6112424062,609.6 -5.7114734444,54.6123940278,609.6 -5.7250027778,54.6257194444,609.6 -5.7383444444,54.6211611111,609.6 + + + + + + EGRU404G NEWTOWNARDS RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7978" txt_name="NEWTOWNARDS RWY 33"><tr><td>543241N 0053834W -<br/>543224N 0053922W -<br/>543304N 0054002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to<br/>543322N 0053916W -<br/>543241N 0053834W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6428055556,54.5446027778,609.6 -5.6543445833,54.556013,609.6 -5.6583959388,54.5541442047,609.6 -5.662720605,54.5524954264,609.6 -5.6672833056,54.5510800833,609.6 -5.6561194444,54.5400444444,609.6 -5.6428055556,54.5446027778,609.6 + + + + + + EGRU406A WALNEY + <table border="1" cellpadding="1" cellspacing="0" row_id="8031" txt_name="WALNEY"><tr><td>A circle, 2 NM radius, centred at 540752N 0031548W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2632277778,54.1643771067,609.6 -3.2690585169,54.1642005933,609.6 -3.2748273013,54.1636729286,609.6 -3.280472839,54.1627997191,609.6 -3.285935157,54.1615902424,609.6 -3.291156242,54.1600573477,609.6 -3.2960806603,54.1582173188,609.6 -3.3006561493,54.1560896996,609.6 -3.3048341738,54.1536970853,609.6 -3.3085704421,54.1510648816,609.6 -3.3118253756,54.1482210329,609.6 -3.3145645274,54.1451957247,609.6 -3.3167589447,54.1420210617,609.6 -3.3183854724,54.1387307264,609.6 -3.319426994,54.1353596202,609.6 -3.3198726078,54.1319434927,609.6 -3.3197177365,54.1285185624,609.6 -3.3189641693,54.125121132,609.6 -3.3176200374,54.1217872042,609.6 -3.3156997208,54.1185520999,609.6 -3.3132236912,54.1154500854,609.6 -3.3102182896,54.1125140096,609.6 -3.306715443,54.1097749575,609.6 -3.3027523237,54.1072619224,609.6 -3.2983709527,54.1050015,609.6 -3.2936177545,54.1030176089,609.6 -3.2885430655,54.1013312379,609.6 -3.2832006024,54.0999602261,609.6 -3.2776468964,54.0989190751,609.6 -3.2719406978,54.0982187963,609.6 -3.2661423583,54.0978667957,609.6 -3.2603131973,54.0978667957,609.6 -3.2545148578,54.0982187963,609.6 -3.2488086591,54.0989190751,609.6 -3.2432549531,54.0999602261,609.6 -3.2379124901,54.1013312379,609.6 -3.2328378011,54.1030176089,609.6 -3.2280846029,54.1050015,609.6 -3.2237032319,54.1072619224,609.6 -3.2197401125,54.1097749575,609.6 -3.216237266,54.1125140096,609.6 -3.2132318643,54.1154500854,609.6 -3.2107558347,54.1185520999,609.6 -3.2088355182,54.1217872042,609.6 -3.2074913862,54.125121132,609.6 -3.2067378191,54.1285185624,609.6 -3.2065829477,54.1319434927,609.6 -3.2070285615,54.1353596202,609.6 -3.2080700832,54.1387307264,609.6 -3.2096966109,54.1420210617,609.6 -3.2118910282,54.1451957247,609.6 -3.21463018,54.1482210329,609.6 -3.2178851135,54.1510648816,609.6 -3.2216213818,54.1536970853,609.6 -3.2257994062,54.1560896996,609.6 -3.2303748952,54.1582173188,609.6 -3.2352993136,54.1600573477,609.6 -3.2405203986,54.1615902424,609.6 -3.2459827166,54.1627997191,609.6 -3.2516282543,54.1636729286,609.6 -3.2573970386,54.1642005933,609.6 -3.2632277778,54.1643771067,609.6 + + + + + + EGRU406B WALNEY RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7653" txt_name="WALNEY RWY 17"><tr><td>541032N 0031742W -<br/>541040N 0031649W -<br/>540949N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to<br/>540939N 0031720W -<br/>541032N 0031742W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.295125,54.1756527778,609.6 -3.2888458333,54.1607845278,609.6 -3.2841622035,54.1620244874,609.6 -3.2793062909,54.1630103456,609.6 -3.2743180556,54.163734,609.6 -3.2802583333,54.1778111111,609.6 -3.295125,54.1756527778,609.6 + + + + + + EGRU406C WALNEY RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7561" txt_name="WALNEY RWY 35"><tr><td>540454N 0031423W -<br/>540447N 0031517W -<br/>540552N 0031544W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to<br/>540557N 0031450W -<br/>540454N 0031423W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2398166667,54.0817777778,609.6 -3.2471365833,54.0991938333,609.6 -3.25211691,54.0984692599,609.6 -3.2571882587,54.0980124281,609.6 -3.2623090833,54.0978270833,609.6 -3.25465,54.0796194444,609.6 -3.2398166667,54.0817777778,609.6 + + + + + + EGRU408A LEEMING + <table border="1" cellpadding="1" cellspacing="0" row_id="7579" txt_name="LEEMING"><tr><td>A circle, 2.5 NM radius, centred at 541733N 0013207W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5352777778,54.3340952335,609.6 -1.5418450861,54.3339176176,609.6 -1.548356196,54.3333862896,609.6 -1.5547553941,54.3325057962,609.6 -1.5609879334,54.3312836713,609.6 -1.567000505,54.3297303713,609.6 -1.572741698,54.3278591848,609.6 -1.5781624417,54.3256861177,609.6 -1.5832164274,54.3232297559,609.6 -1.5878605055,54.3205111044,609.6 -1.5920550547,54.3175534068,609.6 -1.5957643201,54.3143819454,609.6 -1.5989567169,54.3110238238,609.6 -1.6016050982,54.3075077339,609.6 -1.6036869829,54.30386371,609.6 -1.6051847444,54.300122871,609.6 -1.6060857555,54.2963171542,609.6 -1.6063824916,54.292479042,609.6 -1.6060725893,54.2886412841,609.6 -1.6051588604,54.2848366185,609.6 -1.6036492625,54.2810974915,609.6 -1.6015568259,54.2774557822,609.6 -1.5988995367,54.2739425307,609.6 -1.595700179,54.2705876747,609.6 -1.5919861371,54.2674197949,609.6 -1.5877891582,54.2644658728,609.6 -1.5831450801,54.2617510621,609.6 -1.578093524,54.2592984758,609.6 -1.5726775569,54.2571289903,609.6 -1.5669433247,54.2552610693,609.6 -1.5609396611,54.2537106078,609.6 -1.5547176737,54.2524907976,609.6 -1.5483303119,54.2516120162,609.6 -1.5418319199,54.2510817393,609.6 -1.5352777778,54.2509044778,609.6 -1.5287236356,54.2510817393,609.6 -1.5222252436,54.2516120162,609.6 -1.5158378819,54.2524907976,609.6 -1.5096158945,54.2537106078,609.6 -1.5036122309,54.2552610693,609.6 -1.4978779987,54.2571289903,609.6 -1.4924620315,54.2592984758,609.6 -1.4874104755,54.2617510621,609.6 -1.4827663974,54.2644658728,609.6 -1.4785694185,54.2674197949,609.6 -1.4748553766,54.2705876747,609.6 -1.4716560189,54.2739425307,609.6 -1.4689987296,54.2774557822,609.6 -1.466906293,54.2810974915,609.6 -1.4653966952,54.2848366185,609.6 -1.4644829663,54.2886412841,609.6 -1.4641730639,54.292479042,609.6 -1.4644698001,54.2963171542,609.6 -1.4653708112,54.300122871,609.6 -1.4668685726,54.30386371,609.6 -1.4689504574,54.3075077339,609.6 -1.4715988386,54.3110238238,609.6 -1.4747912355,54.3143819454,609.6 -1.4785005008,54.3175534068,609.6 -1.4826950501,54.3205111044,609.6 -1.4873391281,54.3232297559,609.6 -1.4923931138,54.3256861177,609.6 -1.4978138575,54.3278591848,609.6 -1.5035550505,54.3297303713,609.6 -1.5095676221,54.3312836713,609.6 -1.5158001614,54.3325057962,609.6 -1.5221993595,54.3333862896,609.6 -1.5287104694,54.3339176176,609.6 -1.5352777778,54.3340952335,609.6 + + + + + + EGRU408B LEEMING RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="8143" txt_name="LEEMING RWY 16"><tr><td>542028N 0013452W -<br/>542041N 0013402W -<br/>541955N 0013327W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to<br/>541942N 0013417W -<br/>542028N 0013452W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5811833333,54.3410333333,609.6 -1.5713919444,54.3283361944,609.6 -1.5668795474,54.3297655331,609.6 -1.5622023345,54.3310008906,609.6 -1.5573846944,54.3320358333,609.6 -1.5671611111,54.3447194444,609.6 -1.5811833333,54.3410333333,609.6 + + + + + + EGRU408C LEEMING RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="7840" txt_name="LEEMING RWY 34"><tr><td>541438N 0012923W -<br/>541425N 0013013W -<br/>541511N 0013048W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to<br/>541524N 0012958W -<br/>541438N 0012923W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4897166667,54.2440083333,609.6 -1.4993772778,54.2566009444,609.6 -1.5038895877,54.2551807244,609.6 -1.5085646991,54.2539544356,609.6 -1.5133783333,54.2529284167,609.6 -1.5037027778,54.2403222222,609.6 -1.4897166667,54.2440083333,609.6 + + + + + + EGRU408D LEEMING RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="7791" txt_name="LEEMING RWY 03"><tr><td>541517N 0013411W -<br/>541532N 0013459W -<br/>541539N 0013453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to<br/>541521N 0013407W -<br/>541517N 0013411W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5696216944,54.2546920278,609.6 -1.5686279167,54.2557684444,609.6 -1.5730861296,54.2572780563,609.6 -1.5773459603,54.2589728589,609.6 -1.58138525,54.26084375,609.6 -1.5831166667,54.2589676944,609.6 -1.5696216944,54.2546920278,609.6 + + + + + + EGRU408E LEEMING RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7960" txt_name="LEEMING RWY 21"><tr><td>542039N 0013015W -<br/>542024N 0012927W -<br/>541944N 0013003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to<br/>541957N 0013055W -<br/>542039N 0013015W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5042563056,54.3442184167,609.6 -1.5152062778,54.3324053056,609.6 -1.5103125354,54.3314499726,609.6 -1.505550483,54.3302895303,609.6 -1.5009450833,54.3289303333,609.6 -1.4907334444,54.3399428056,609.6 -1.5042563056,54.3442184167,609.6 + + + + + + EGRU409A TEESSIDE INTERNATIONAL + <table border="1" cellpadding="1" cellspacing="0" row_id="7611" txt_name="TEESSIDE INTERNATIONAL"><tr><td>A circle, 2.5 NM radius, centred at 543033N 0012546W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4294444444,54.5507603988,609.6 -1.436046508,54.5505827878,609.6 -1.4425920743,54.5500514747,609.6 -1.449025134,54.5491710062,609.6 -1.4552906489,54.547948916,609.6 -1.4613350273,54.5463956606,609.6 -1.4671065851,54.5445245284,609.6 -1.4725559916,54.5423515254,609.6 -1.4776366926,54.539895237,609.6 -1.4823053102,54.5371766681,609.6 -1.4865220138,54.534219062,609.6 -1.4902508599,54.5310477007,609.6 -1.4934600974,54.5276896871,609.6 -1.4961224369,54.5241737127,609.6 -1.4982152799,54.520529811,609.6 -1.4997209079,54.5167891002,609.6 -1.5006266288,54.5129835166,609.6 -1.5009248799,54.5091455415,609.6 -1.500613287,54.5053079237,609.6 -1.4996946787,54.5015033997,609.6 -1.4981770565,54.4977644147,609.6 -1.4960735209,54.4941228462,609.6 -1.4934021546,54.4906097331,609.6 -1.4901858634,54.4872550114,609.6 -1.4864521771,54.4840872604,609.6 -1.4822330114,54.4811334602,609.6 -1.4775643938,54.4784187631,609.6 -1.4724861548,54.4759662806,609.6 -1.4670415886,54.4737968879,609.6 -1.4612770844,54.4719290476,609.6 -1.4552417328,54.4703786535,609.6 -1.4489869105,54.4691588966,609.6 -1.442565845,54.4682801539,609.6 -1.4360331662,54.4677499004,609.6 -1.4294444444,54.4675726466,609.6 -1.4228557227,54.4677499004,609.6 -1.4163230438,54.4682801539,609.6 -1.4099019784,54.4691588966,609.6 -1.4036471561,54.4703786535,609.6 -1.3976118045,54.4719290476,609.6 -1.3918473003,54.4737968879,609.6 -1.3864027341,54.4759662806,609.6 -1.3813244951,54.4784187631,609.6 -1.3766558775,54.4811334602,609.6 -1.3724367118,54.4840872604,609.6 -1.3687030255,54.4872550114,609.6 -1.3654867343,54.4906097331,609.6 -1.362815368,54.4941228462,609.6 -1.3607118324,54.4977644147,609.6 -1.3591942102,54.5015033997,609.6 -1.3582756019,54.5053079237,609.6 -1.357964009,54.5091455415,609.6 -1.3582622601,54.5129835166,609.6 -1.359167981,54.5167891002,609.6 -1.360673609,54.520529811,609.6 -1.362766452,54.5241737127,609.6 -1.3654287915,54.5276896871,609.6 -1.368638029,54.5310477007,609.6 -1.3723668751,54.534219062,609.6 -1.3765835787,54.5371766681,609.6 -1.3812521963,54.539895237,609.6 -1.3863328973,54.5423515254,609.6 -1.3917823038,54.5445245284,609.6 -1.3975538616,54.5463956606,609.6 -1.40359824,54.547948916,609.6 -1.4098637549,54.5491710062,609.6 -1.4162968146,54.5500514747,609.6 -1.4228423809,54.5505827878,609.6 -1.4294444444,54.5507603988,609.6 + + + + + + EGRU409B TEESSIDE INTERNATIONAL RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8006" txt_name="TEESSIDE INTERNATIONAL RWY 05"><tr><td>542807N 0012938W -<br/>542831N 0013016W -<br/>542904N 0012913W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to<br/>542840N 0012836W -<br/>542807N 0012938W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4940166667,54.468525,609.6 -1.4765378333,54.4778849722,609.6 -1.4802882836,54.4799412982,609.6 -1.4837748599,54.4821495716,609.6 -1.4869794167,54.4844983333,609.6 -1.5044444444,54.4751444444,609.6 -1.4940166667,54.468525,609.6 + + + + + + EGRU409C TEESSIDE INTERNATIONAL RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7766" txt_name="TEESSIDE INTERNATIONAL RWY 23"><tr><td>543259N 0012153W -<br/>543235N 0012115W -<br/>543202N 0012219W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to<br/>543226N 0012256W -<br/>543259N 0012153W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3646916667,54.5498027778,609.6 -1.3822803611,54.5404305,609.6 -1.3785290961,54.5383711288,609.6 -1.3750432165,54.5361598086,609.6 -1.3718408611,54.5338080556,609.6 -1.3542388889,54.5431861111,609.6 -1.3646916667,54.5498027778,609.6 + + + + + + EGRU410A TOPCLIFFE + <table border="1" cellpadding="1" cellspacing="0" row_id="8181" txt_name="TOPCLIFFE"><tr><td>A circle, 2 NM radius, centred at 541220N 0012254W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3816277778,54.2389044702,609.6 -1.3874690187,54.2387279586,609.6 -1.3932481928,54.2382002993,609.6 -1.3989038975,54.2373270988,609.6 -1.4043760513,54.2361176346,609.6 -1.4096065363,54.2345847561,609.6 -1.4145398186,54.2327447467,609.6 -1.4191235415,54.2306171503,609.6 -1.4233090821,54.2282245621,609.6 -1.4270520693,54.2255923874,609.6 -1.4303128533,54.2227485706,609.6 -1.4330569254,54.2197232969,609.6 -1.4352552811,54.2165486709,609.6 -1.4368847239,54.2132583746,609.6 -1.4379281072,54.209887309,609.6 -1.4383745099,54.2064712235,609.6 -1.4382193472,54.203046336,609.6 -1.437464412,54.1996489489,609.6 -1.4361178506,54.1963150643,609.6 -1.4341940696,54.1930800027,609.6 -1.4317135777,54.1899780297,609.6 -1.4287027635,54.1870419937,609.6 -1.4251936121,54.1843029793,609.6 -1.4212233625,54.1817899792,609.6 -1.4168341115,54.1795295888,609.6 -1.4120723669,54.1775457259,609.6 -1.4069885556,54.1758593791,609.6 -1.4016364907,54.1744883872,609.6 -1.3960728045,54.1734472513,609.6 -1.3903563526,54.1727469828,609.6 -1.3845475949,54.1723949873,609.6 -1.3787079606,54.1723949873,609.6 -1.372899203,54.1727469828,609.6 -1.3671827511,54.1734472513,609.6 -1.3616190649,54.1744883872,609.6 -1.356267,54.1758593791,609.6 -1.3511831886,54.1775457259,609.6 -1.3464214441,54.1795295888,609.6 -1.342032193,54.1817899792,609.6 -1.3380619434,54.1843029793,609.6 -1.334552792,54.1870419937,609.6 -1.3315419779,54.1899780297,609.6 -1.329061486,54.1930800027,609.6 -1.3271377049,54.1963150643,609.6 -1.3257911435,54.1996489489,609.6 -1.3250362084,54.203046336,609.6 -1.3248810456,54.2064712235,609.6 -1.3253274484,54.209887309,609.6 -1.3263708316,54.2132583746,609.6 -1.3280002745,54.2165486709,609.6 -1.3301986301,54.2197232969,609.6 -1.3329427022,54.2227485706,609.6 -1.3362034863,54.2255923874,609.6 -1.3399464734,54.2282245621,609.6 -1.3441320141,54.2306171503,609.6 -1.3487157369,54.2327447467,609.6 -1.3536490193,54.2345847561,609.6 -1.3588795043,54.2361176346,609.6 -1.3643516581,54.2373270988,609.6 -1.3700073628,54.2382002993,609.6 -1.3757865369,54.2387279586,609.6 -1.3816277778,54.2389044702,609.6 + + + + + + EGRU410B TOPCLIFFE RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="8164" txt_name="TOPCLIFFE RWY 02"><tr><td>540928N 0012421W -<br/>540940N 0012512W -<br/>541036N 0012434W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541024N 0012343W -<br/>540928N 0012421W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.40583975,54.1578682778,609.6 -1.3953372778,54.1733367778,609.6 -1.4002433356,54.1741926445,609.6 -1.4049981522,54.1753043042,609.6 -1.4095630833,54.1766627222,609.6 -1.4200591667,54.1611958056,609.6 -1.40583975,54.1578682778,609.6 + + + + + + EGRU410C TOPCLIFFE RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="7817" txt_name="TOPCLIFFE RWY 20"><tr><td>541524N 0012119W -<br/>541512N 0012027W -<br/>541405N 0012113W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541417N 0012204W -<br/>541524N 0012119W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3551701389,54.2566158889,609.6 -1.3679102222,54.2379189722,609.6 -1.3629969339,54.2370624949,609.6 -1.3582356996,54.2359498656,609.6 -1.3536653611,54.2345901667,609.6 -1.3409179167,54.2532884167,609.6 -1.3551701389,54.2566158889,609.6 + + + + + + EGRU410D TOPCLIFFE RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="7609" txt_name="TOPCLIFFE RWY 13"><tr><td>541355N 0012720W -<br/>541421N 0012647W -<br/>541344N 0012520W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541318N 0012553W -<br/>541355N 0012720W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4554805,54.2318486944,609.6 -1.4313874444,54.2216514722,609.6 -1.428721035,54.2242160026,609.6 -1.4256705754,54.2266291543,609.6 -1.4222608889,54.22887125,609.6 -1.4464896111,54.2391268611,609.6 -1.4554805,54.2318486944,609.6 + + + + + + EGRU410E TOPCLIFFE RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="7671" txt_name="TOPCLIFFE RWY 31"><tr><td>541053N 0011838W -<br/>541027N 0011910W -<br/>541059N 0012024W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541125N 0011953W -<br/>541053N 0011838W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3105919444,54.1814746111,609.6 -1.3312787778,54.1902709444,609.6 -1.3338459199,54.1876725655,609.6 -1.3368016981,54.185220428,609.6 -1.340122,54.1829344722,609.6 -1.3195703333,54.1741963889,609.6 -1.3105919444,54.1814746111,609.6 + + + + + + EGRU410F TOPCLIFFE RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="13483" txt_name="TOPCLIFFE RWY 07"><tr><td>541107N 0012746W -<br/>541138N 0012800W -<br/>541155N 0012614W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541124N 0012555W -<br/>541107N 0012746W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.4628026944,54.1851534167,609.6 -1.4318126944,54.1900875,609.6 -1.4340062649,54.1928130821,609.6 -1.4357705656,54.1956438446,609.6 -1.4370910556,54.1985565833,609.6 -1.4668027778,54.1938257778,609.6 -1.4628026944,54.1851534167,609.6 + + + + + + EGRU410G TOPCLIFFE RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="13484" txt_name="TOPCLIFFE RWY 25"><tr><td>541311N 0011812W -<br/>541240N 0011758W -<br/>541225N 0011930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to<br/>541257N 0011939W -<br/>541311N 0011812W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3034665833,54.2197288889,609.6 -1.3276355556,54.215912,609.6 -1.3262713683,54.2130061059,609.6 -1.3253615157,54.2100397783,609.6 -1.3249133611,54.2070373611,609.6 -1.299464,54.2110565833,609.6 -1.3034665833,54.2197288889,609.6 + + + + + + EGRU411A ISLE OF MAN + <table border="1" cellpadding="1" cellspacing="0" row_id="8500" txt_name="ISLE OF MAN"><tr><td>A circle, 2.7 NM radius, centred at 540500N 0043724W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>Restricted airspace active H24. Small unmanned aircraft flight not permitted except with the permission of the Isle of Man CAA. Contact caa@gov.im or 01624-682358</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6233333333,54.1282577424,30449.52 -4.6300934172,54.1280817561,30449.52 -4.6368004237,54.1275551791,30449.52 -4.6434016959,54.1266821455,30449.52 -4.6498454151,54.1254695096,30449.52 -4.6560810113,54.1239267908,30449.52 -4.6620595627,54.1220660988,30449.52 -4.667734183,54.1199020374,30449.52 -4.6730603909,54.117451589,30449.52 -4.6779964608,54.1147339801,30449.52 -4.6825037501,54.1117705296,30449.52 -4.6865470027,54.1085844801,30449.52 -4.6900946234,54.1052008146,30449.52 -4.6931189245,54.1016460595,30449.52 -4.6955963394,54.0979480755,30449.52 -4.6975076042,54.0941358383,30449.52 -4.6988379044,54.0902392109,30449.52 -4.6995769864,54.0862887089,30449.52 -4.6997192325,54.0823152611,30449.52 -4.6992637003,54.0783499674,30449.52 -4.6982141239,54.0744238547,30449.52 -4.6965788803,54.0705676349,30449.52 -4.694370918,54.0668114647,30449.52 -4.6916076513,54.0631847104,30449.52 -4.6883108199,54.0597157192,30449.52 -4.6845063152,54.0564315982,30449.52 -4.6802239747,54.0533580037,30449.52 -4.675497347,54.050518942,30449.52 -4.6703634275,54.0479365828,30449.52 -4.6648623697,54.0456310874,30449.52 -4.6590371708,54.0436204524,30449.52 -4.6529333379,54.0419203703,30449.52 -4.6465985335,54.0405441082,30449.52 -4.6400822067,54.0395024049,30449.52 -4.6334352097,54.0388033878,30449.52 -4.6267094045,54.0384525106,30449.52 -4.6199572621,54.0384525106,30449.52 -4.613231457,54.0388033878,30449.52 -4.60658446,54.0395024049,30449.52 -4.6000681332,54.0405441082,30449.52 -4.5937333288,54.0419203703,30449.52 -4.5876294958,54.0436204524,30449.52 -4.581804297,54.0456310874,30449.52 -4.5763032391,54.0479365828,30449.52 -4.5711693197,54.050518942,30449.52 -4.5664426919,54.0533580037,30449.52 -4.5621603515,54.0564315982,30449.52 -4.5583558468,54.0597157192,30449.52 -4.5550590154,54.0631847104,30449.52 -4.5522957487,54.0668114647,30449.52 -4.5500877864,54.0705676349,30449.52 -4.5484525427,54.0744238547,30449.52 -4.5474029664,54.0783499674,30449.52 -4.5469474342,54.0823152611,30449.52 -4.5470896803,54.0862887089,30449.52 -4.5478287623,54.0902392109,30449.52 -4.5491590625,54.0941358383,30449.52 -4.5510703273,54.0979480755,30449.52 -4.5535477422,54.1016460595,30449.52 -4.5565720433,54.1052008146,30449.52 -4.560119664,54.1085844801,30449.52 -4.5641629166,54.1117705296,30449.52 -4.5686702059,54.1147339801,30449.52 -4.5736062758,54.117451589,30449.52 -4.5789324837,54.1199020374,30449.52 -4.584607104,54.1220660988,30449.52 -4.5905856554,54.1239267908,30449.52 -4.5968212515,54.1254695096,30449.52 -4.6032649708,54.1266821455,30449.52 -4.609866243,54.1275551791,30449.52 -4.6165732494,54.1280817561,30449.52 -4.6233333333,54.1282577424,30449.52 + + + + + + EGRU412 ISLE OF MAN PRISON + <table border="1" cellpadding="1" cellspacing="0" row_id="8507" txt_name="ISLE OF MAN PRISON"><tr><td>542124N 0043154W -<br/>542128N 0043151W -<br/>542129N 0043150W -<br/>542133N 0043143W -<br/>542132N 0043141W -<br/>542117N 0043127W -<br/>542114N 0043143W -<br/>542113N 0043153W -<br/>542116N 0043201W -<br/>542117N 0043201W -<br/>542124N 0043154W <br/>Upper limit: UNL<br/>Lower limit: SFC <br/>Class: </td><td>Restricted airspace active H24. Contact caa@gov.im or 01624-682358 for further details</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5316583333,54.3567583333,30449.52 -4.5337277778,54.3548138889,30449.52 -4.5336166667,54.3545555556,30449.52 -4.5313527778,54.353625,30449.52 -4.5287194444,54.3537555556,30449.52 -4.5241055556,54.3547611111,30449.52 -4.5280277778,54.3588777778,30449.52 -4.5287472222,54.3592833333,30449.52 -4.5304888889,54.3580611111,30449.52 -4.5308222222,54.3577472222,30449.52 -4.5316583333,54.3567583333,30449.52 + + + + + + EGRU413 HMP DEERBOLT + <table border="1" cellpadding="1" cellspacing="0" row_id="14079" txt_name="HMP DEERBOLT"><tr><td>543255N 0015600W -<br/>543222N 0015541W -<br/>543214N 0015609W -<br/>543221N 0015700W -<br/>543244N 0015701W -<br/>543255N 0015600W <br/>Upper limit: 1100 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 602 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.9334416667,54.5484861111,335.28000000000003 -1.9503194444,54.5456166667,335.28000000000003 -1.9500527778,54.5391583333,335.28000000000003 -1.9359555556,54.5372027778,335.28000000000003 -1.9281472222,54.5393777778,335.28000000000003 -1.9334416667,54.5484861111,335.28000000000003 + + + + + + EGRU414 HMP DURHAM + <table border="1" cellpadding="1" cellspacing="0" row_id="14112" txt_name="HMP DURHAM"><tr><td>544641N 0013402W -<br/>544635N 0013340W -<br/>544614N 0013337W -<br/>544602N 0013352W -<br/>544609N 0013429W -<br/>544637N 0013440W -<br/>544641N 0013402W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 196 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5670861111,54.7781138889,182.88 -1.5776388889,54.7768805556,182.88 -1.5746444444,54.7692666667,182.88 -1.5645666667,54.7673194444,182.88 -1.5601888889,54.7706861111,182.88 -1.5609722222,54.7763472222,182.88 -1.5670861111,54.7781138889,182.88 + + + + + + EGRU415 HMP FRANKLAND/LOW NEWTON + <table border="1" cellpadding="1" cellspacing="0" row_id="14141" txt_name="HMP FRANKLAND/LOW NEWTON"><tr><td>544839N 0013233W -<br/>544800N 0013221W -<br/>544753N 0013317W -<br/>544810N 0013351W -<br/>544832N 0013351W -<br/>544839N 0013233W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 208 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.5424833333,54.8109194444,213.36 -1.5641277778,54.8088,213.36 -1.564175,54.8027777778,213.36 -1.5547861111,54.7981777778,213.36 -1.5392111111,54.8001333333,213.36 -1.5424833333,54.8109194444,213.36 + + + + + + EGRU416 HMP HOLME HOUSE + <table border="1" cellpadding="1" cellspacing="0" row_id="14127" txt_name="HMP HOLME HOUSE"><tr><td>543500N 0011748W -<br/>543500N 0011715W -<br/>543433N 0011658W -<br/>543422N 0011718W -<br/>543423N 0011748W -<br/>543435N 0011809W -<br/>543448N 0011809W -<br/>543500N 0011748W <br/>Upper limit: 500 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 39 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2967611111,54.5833138889,152.4 -1.302475,54.5800361111,152.4 -1.3024944444,54.5763805556,152.4 -1.2966055556,54.5729222222,152.4 -1.2882555556,54.5729055556,152.4 -1.2827388889,54.5759472222,152.4 -1.2874805556,54.58325,152.4 -1.2967611111,54.5833138889,152.4 + + + + + + EGRU417 HMP LANCASTER FARMS + <table border="1" cellpadding="1" cellspacing="0" row_id="14098" txt_name="HMP LANCASTER FARMS"><tr><td>540337N 0024623W -<br/>540334N 0024557W -<br/>540325N 0024544W -<br/>540304N 0024548W -<br/>540255N 0024607W -<br/>540256N 0024629W -<br/>540309N 0024645W -<br/>540329N 0024641W -<br/>540337N 0024623W <br/>Upper limit: 700 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 238 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7730277778,54.0601888889,213.36 -2.7780666667,54.058,213.36 -2.7792722222,54.0525166667,213.36 -2.7747222222,54.0490194444,213.36 -2.7687166667,54.0486583333,213.36 -2.7634277778,54.0510416667,213.36 -2.7621972222,54.0569194444,213.36 -2.7657555556,54.0595777778,213.36 -2.7730277778,54.0601888889,213.36 + + + + + + EGRU501A LONDONDERRY/EGLINTON + <table border="1" cellpadding="1" cellspacing="0" row_id="7745" txt_name="LONDONDERRY/EGLINTON"><tr><td>A circle, 2.5 NM radius, centred at 550234N 0070943W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.1619444444,55.084367829,609.6 -7.16863411,55.0841902302,609.6 -7.1752665251,55.0836589535,609.6 -7.1817849341,55.0827785455,609.6 -7.1881335654,55.08155654,609.6 -7.1942581135,55.0800033933,609.6 -7.2001062067,55.0781323936,609.6 -7.205627858,55.0759595465,609.6 -7.2107758951,55.0735034372,609.6 -7.2155063643,55.07078507,609.6 -7.2197789075,55.0678276874,609.6 -7.2235571058,55.0646565705,609.6 -7.2268087892,55.0612988211,609.6 -7.2295063091,55.0577831292,609.6 -7.2316267707,55.0541395266,609.6 -7.2331522246,55.0503991296,609.6 -7.2340698146,55.0465938723,609.6 -7.2343718823,55.0427562335,609.6 -7.2340560266,55.038918959,609.6 -7.2331251182,55.0351147825,609.6 -7.2315872689,55.0313761459,609.6 -7.229455757,55.0277349233,609.6 -7.2267489084,55.0242221499,609.6 -7.2234899355,55.0208677583,609.6 -7.2197067351,55.0177003241,609.6 -7.2154316474,55.0147468236,609.6 -7.2107011782,55.0120324057,609.6 -7.2055556855,55.0095801785,609.6 -7.2000390363,55.0074110141,609.6 -7.1941982326,55.0055433721,609.6 -7.1880830132,55.003993144,609.6 -7.1817454321,55.0027735185,609.6 -7.1752394186,55.0018948709,609.6 -7.1686203219,55.001364675,609.6 -7.1619444444,55.0011874405,609.6 -7.1552685669,55.001364675,609.6 -7.1486494703,55.0018948709,609.6 -7.1421434567,55.0027735185,609.6 -7.1358058756,55.003993144,609.6 -7.1296906563,55.0055433721,609.6 -7.1238498526,55.0074110141,609.6 -7.1183332034,55.0095801785,609.6 -7.1131877107,55.0120324057,609.6 -7.1084572414,55.0147468236,609.6 -7.1041821538,55.0177003241,609.6 -7.1003989534,55.0208677583,609.6 -7.0971399805,55.0242221499,609.6 -7.0944331319,55.0277349233,609.6 -7.09230162,55.0313761459,609.6 -7.0907637707,55.0351147825,609.6 -7.0898328623,55.038918959,609.6 -7.0895170066,55.0427562335,609.6 -7.0898190743,55.0465938723,609.6 -7.0907366643,55.0503991296,609.6 -7.0922621182,55.0541395266,609.6 -7.0943825798,55.0577831292,609.6 -7.0970800997,55.0612988211,609.6 -7.1003317831,55.0646565705,609.6 -7.1041099814,55.0678276874,609.6 -7.1083825246,55.07078507,609.6 -7.1131129938,55.0735034372,609.6 -7.1182610309,55.0759595465,609.6 -7.1237826822,55.0781323936,609.6 -7.1296307754,55.0800033933,609.6 -7.1357553235,55.08155654,609.6 -7.1421039548,55.0827785455,609.6 -7.1486223637,55.0836589535,609.6 -7.1552547789,55.0841902302,609.6 -7.1619444444,55.084367829,609.6 + + + + + + EGRU501B LONDONDERRY/EGLINTON RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7685" txt_name="LONDONDERRY/EGLINTON RWY 08"><tr><td>550123N 0071453W -<br/>550154N 0071509W -<br/>550206N 0071359W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to<br/>550135N 0071343W -<br/>550123N 0071453W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.2479777778,55.0229694444,609.6 -7.2284896389,55.02637775,609.6 -7.2303766768,55.029174606,609.6 -7.2319081121,55.0320422966,609.6 -7.2330759167,55.0349659167,609.6 -7.2525111111,55.0315666667,609.6 -7.2479777778,55.0229694444,609.6 + + + + + + EGRU501C LONDONDERRY/EGLINTON RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="7583" txt_name="LONDONDERRY/EGLINTON RWY 26"><tr><td>550345N 0070429W -<br/>550314N 0070412W -<br/>550301N 0070527W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to<br/>550332N 0070543W -<br/>550345N 0070429W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.0746277778,55.0625416667,609.6 -7.0952194167,55.0589717778,609.6 -7.0933618418,55.056167767,609.6 -7.091861437,55.0532941684,609.6 -7.0907259444,55.0503659444,609.6 -7.0700833333,55.0539444444,609.6 -7.0746277778,55.0625416667,609.6 + + + + + + EGRU502A ISLAY + <table border="1" cellpadding="1" cellspacing="0" row_id="8140" txt_name="ISLAY"><tr><td>A circle, 2 NM radius, centred at 554100N 0061535W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2597222222,55.7166018889,609.6 -6.2657819823,55.7164254124,609.6 -6.271777345,55.7158978586,609.6 -6.2776446024,55.7150248334,609.6 -6.2833214183,55.7138156138,609.6 -6.2887474943,55.712283048,609.6 -6.2938652149,55.7104434183,609.6 -6.2986202621,55.7083162666,609.6 -6.3029621938,55.705924186,609.6 -6.3068449806,55.7032925788,609.6 -6.3102274936,55.7004493856,609.6 -6.313073939,55.6974247876,609.6 -6.3153542352,55.6942508839,609.6 -6.3170443274,55.6909613507,609.6 -6.318126438,55.6875910823,609.6 -6.3185892489,55.6841758205,609.6 -6.3184280152,55.6807517748,609.6 -6.3176446087,55.6773552385,609.6 -6.316247491,55.674022204,609.6 -6.3142516173,55.6707879818,609.6 -6.3116782717,55.6676868271,609.6 -6.3085548363,55.6647515777,609.6 -6.3049144963,55.6620133077,609.6 -6.3007958855,55.6595009996,609.6 -6.2962426744,55.6572412388,609.6 -6.291303107,55.6552579343,609.6 -6.2860294903,55.6535720664,609.6 -6.2804776422,55.6522014666,609.6 -6.2747063031,55.6511606303,609.6 -6.2687765182,55.650460564,609.6 -6.2627509957,55.6501086704,609.6 -6.2566934487,55.6501086704,609.6 -6.2506679263,55.650460564,609.6 -6.2447381414,55.6511606303,609.6 -6.2389668023,55.6522014666,609.6 -6.2334149541,55.6535720664,609.6 -6.2281413375,55.6552579343,609.6 -6.22320177,55.6572412388,609.6 -6.2186485589,55.6595009996,609.6 -6.2145299481,55.6620133077,609.6 -6.2108896082,55.6647515777,609.6 -6.2077661728,55.6676868271,609.6 -6.2051928272,55.6707879818,609.6 -6.2031969535,55.674022204,609.6 -6.2017998358,55.6773552385,609.6 -6.2010164292,55.6807517748,609.6 -6.2008551956,55.6841758205,609.6 -6.2013180065,55.6875910823,609.6 -6.202400117,55.6909613507,609.6 -6.2040902092,55.6942508839,609.6 -6.2063705054,55.6974247876,609.6 -6.2092169508,55.7004493856,609.6 -6.2125994638,55.7032925788,609.6 -6.2164822507,55.705924186,609.6 -6.2208241824,55.7083162666,609.6 -6.2255792295,55.7104434183,609.6 -6.2306969501,55.712283048,609.6 -6.2361230262,55.7138156138,609.6 -6.241799842,55.7150248334,609.6 -6.2476670995,55.7158978586,609.6 -6.2536624622,55.7164254124,609.6 -6.2597222222,55.7166018889,609.6 + + + + + + EGRU502B ISLAY RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="8030" txt_name="ISLAY RWY 07"><tr><td>553948N 0061952W -<br/>554018N 0062011W -<br/>554032N 0061901W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to<br/>554002N 0061840W -<br/>553948N 0061952W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3310583333,55.6632111111,609.6 -6.3112065278,55.6671968889,609.6 -6.3135733497,55.6698858046,609.6 -6.3155017861,55.6726843614,609.6 -6.3169760278,55.6755697778,609.6 -6.3363611111,55.6716777778,609.6 -6.3310583333,55.6632111111,609.6 + + + + + + EGRU502C ISLAY RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7735" txt_name="ISLAY RWY 25"><tr><td>554212N 0061040W -<br/>554142N 0061021W -<br/>554121N 0061206W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to<br/>554152N 0061224W -<br/>554212N 0061040W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.1778694444,55.7033861111,609.6 -6.20656975,55.6976632222,609.6 -6.2045004609,55.6948971441,609.6 -6.2028814671,55.6920369256,609.6 -6.2017258611,55.6891058889,609.6 -6.1725583333,55.6949222222,609.6 -6.1778694444,55.7033861111,609.6 + + + + + + EGRU502D ISLAY RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="7727" txt_name="ISLAY RWY 12"><tr><td>554220N 0062026W -<br/>554248N 0061957W -<br/>554215N 0061820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to<br/>554147N 0061850W -<br/>554220N 0062026W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3406861111,55.7055111111,609.6 -6.3138358611,55.6964641944,609.6 -6.3115212547,55.6991669056,609.6 -6.3087842929,55.7017407062,609.6 -6.3056472222,55.7041646111,609.6 -6.3325194444,55.7132194444,609.6 -6.3406861111,55.7055111111,609.6 + + + + + + EGRU502E ISLAY RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="7754" txt_name="ISLAY RWY 30"><tr><td>553941N 0061044W -<br/>553913N 0061113W -<br/>553945N 0061249W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to<br/>554013N 0061220W -<br/>553941N 0061044W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.1788166667,55.6612916667,609.6 -6.2055239444,55.6703383333,609.6 -6.2078192916,55.667630681,609.6 -6.2105368535,55.6650509551,609.6 -6.2136544444,55.6626201389,609.6 -6.1869666667,55.6535805556,609.6 -6.1788166667,55.6612916667,609.6 + + + + + + EGRU503A CAMPBELTOWN + <table border="1" cellpadding="1" cellspacing="0" row_id="7731" txt_name="CAMPBELTOWN"><tr><td>A circle, 2 NM radius, centred at 552615N 0054117W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.6881,55.4708865645,609.6 -5.6941220147,55.4707100823,609.6 -5.7000800346,55.4701825112,609.6 -5.7059107502,55.4693094573,609.6 -5.7115522144,55.4681001977,609.6 -5.7169445058,55.4665675807,609.6 -5.7220303684,55.4647278888,609.6 -5.7267558229,55.4626006643,609.6 -5.7310707415,55.4602085004,609.6 -5.7349293813,55.4575768001,609.6 -5.7382908687,55.4547335046,609.6 -5.7411196321,55.4517087954,609.6 -5.7433857756,55.448534773,609.6 -5.7450653929,55.4452451142,609.6 -5.7461408152,55.4418747144,609.6 -5.746600793,55.4384593168,609.6 -5.746440609,55.4350351322,609.6 -5.7456621213,55.4316384554,609.6 -5.744273737,55.4283052805,609.6 -5.7422903165,55.4250709195,609.6 -5.73973301,55.4219696294,609.6 -5.7366290279,55.4190342499,609.6 -5.7330113481,55.4162958566,609.6 -5.7289183635,55.4137834338,609.6 -5.7243934726,55.4115235687,609.6 -5.7194846198,55.4095401715,609.6 -5.7142437872,55.4078542242,609.6 -5.7087264464,55.4064835594,609.6 -5.7029909739,55.4054426733,609.6 -5.6970980365,55.4047425735,609.6 -5.6911099543,55.404390663,609.6 -5.6850900457,55.404390663,609.6 -5.6791019635,55.4047425735,609.6 -5.6732090261,55.4054426733,609.6 -5.6674735536,55.4064835594,609.6 -5.6619562128,55.4078542242,609.6 -5.6567153802,55.4095401715,609.6 -5.6518065274,55.4115235687,609.6 -5.6472816365,55.4137834338,609.6 -5.6431886519,55.4162958566,609.6 -5.6395709721,55.4190342499,609.6 -5.63646699,55.4219696294,609.6 -5.6339096835,55.4250709195,609.6 -5.631926263,55.4283052805,609.6 -5.6305378787,55.4316384554,609.6 -5.629759391,55.4350351322,609.6 -5.629599207,55.4384593168,609.6 -5.6300591848,55.4418747144,609.6 -5.6311346071,55.4452451142,609.6 -5.6328142244,55.448534773,609.6 -5.6350803679,55.4517087954,609.6 -5.6379091313,55.4547335046,609.6 -5.6412706187,55.4575768001,609.6 -5.6451292585,55.4602085004,609.6 -5.6494441771,55.4626006643,609.6 -5.6541696316,55.4647278888,609.6 -5.6592554942,55.4665675807,609.6 -5.6646477856,55.4681001977,609.6 -5.6702892498,55.4693094573,609.6 -5.6761199654,55.4701825112,609.6 -5.6820779853,55.4707100823,609.6 -5.6881,55.4708865645,609.6 + + + + + + EGRU503B CAMPBELTOWN RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="8166" txt_name="CAMPBELTOWN RWY 11"><tr><td>552646N 0054608W -<br/>552717N 0054552W -<br/>552704N 0054430W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to<br/>552633N 0054446W -<br/>552646N 0054608W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.7688818889,55.4461494167,609.6 -5.74600975,55.4424185278,609.6 -5.7450145588,55.4453669439,609.6 -5.7435556738,55.4482523464,609.6 -5.7416448611,55.4510512222,609.6 -5.7645058056,55.4547803611,609.6 -5.7688818889,55.4461494167,609.6 + + + + + + EGRU503C CAMPBELTOWN RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7813" txt_name="CAMPBELTOWN RWY 29"><tr><td>552535N 0053529W -<br/>552504N 0053544W -<br/>552527N 0053804W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to<br/>552558N 0053749W -<br/>552535N 0053529W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.5912708611,55.4263978889,609.6 -5.6302008333,55.4328010278,609.6 -5.6312021234,55.4298533037,609.6 -5.6326664256,55.4269688867,609.6 -5.63458175,55.42417125,609.6 -5.5956437778,55.4177668889,609.6 -5.5912708611,55.4263978889,609.6 + + + + + + EGRU504A PRESTWICK + <table border="1" cellpadding="1" cellspacing="0" row_id="7696" txt_name="PRESTWICK"><tr><td>A circle, 2.5 NM radius, centred at 553034N 0043540W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5945805556,55.5509785198,609.6 -4.6013492444,55.5508009314,609.6 -4.6080600036,55.550269686,609.6 -4.6146554036,55.5493893301,609.6 -4.6210790116,55.5481673976,609.6 -4.6272758781,55.5466143445,609.6 -4.6331930109,55.5447434589,609.6 -4.6387798314,55.5425707464,609.6 -4.6439886091,55.5401147917,609.6 -4.6487748714,55.5373965986,609.6 -4.6530977841,55.5344394092,609.6 -4.6569204995,55.5312685036,609.6 -4.6602104698,55.5279109828,609.6 -4.6629397226,55.5243955356,609.6 -4.6650850957,55.5207521923,609.6 -4.6666284315,55.5170120675,609.6 -4.6675567258,55.5132070933,609.6 -4.6678622339,55.5093697465,609.6 -4.6675425307,55.5055327706,609.6 -4.6666005248,55.5017288963,609.6 -4.6650444277,55.4979905628,609.6 -4.6628876781,55.4943496414,609.6 -4.6601488213,55.4908371641,609.6 -4.6568513462,55.4874830602,609.6 -4.6530234809,55.4843159021,609.6 -4.6486979487,55.4813626631,609.6 -4.6439116863,55.4786484888,609.6 -4.6387055281,55.4761964845,609.6 -4.6331238575,55.4740275195,609.6 -4.6272142294,55.4721600508,609.6 -4.621026967,55.4706099677,609.6 -4.6146147355,55.469390457,609.6 -4.6080320968,55.4685118925,609.6 -4.6013350494,55.4679817469,609.6 -4.5945805556,55.4678045293,609.6 -4.5878260617,55.4679817469,609.6 -4.5811290143,55.4685118925,609.6 -4.5745463757,55.469390457,609.6 -4.5681341441,55.4706099677,609.6 -4.5619468817,55.4721600508,609.6 -4.5560372536,55.4740275195,609.6 -4.550455583,55.4761964845,609.6 -4.5452494248,55.4786484888,609.6 -4.5404631624,55.4813626631,609.6 -4.5361376302,55.4843159021,609.6 -4.5323097649,55.4874830602,609.6 -4.5290122898,55.4908371641,609.6 -4.526273433,55.4943496414,609.6 -4.5241166834,55.4979905628,609.6 -4.5225605863,55.5017288963,609.6 -4.5216185804,55.5055327706,609.6 -4.5212988772,55.5093697465,609.6 -4.5216043854,55.5132070933,609.6 -4.5225326796,55.5170120675,609.6 -4.5240760154,55.5207521923,609.6 -4.5262213885,55.5243955356,609.6 -4.5289506413,55.5279109828,609.6 -4.5322406116,55.5312685036,609.6 -4.536063327,55.5344394092,609.6 -4.5403862397,55.5373965986,609.6 -4.545172502,55.5401147917,609.6 -4.5503812797,55.5425707464,609.6 -4.5559681002,55.5447434589,609.6 -4.561885233,55.5466143445,609.6 -4.5680820995,55.5481673976,609.6 -4.5745057075,55.5493893301,609.6 -4.5811011075,55.550269686,609.6 -4.5878118667,55.5508009314,609.6 -4.5945805556,55.5509785198,609.6 + + + + + + EGRU504B PRESTWICK RWY 02 + <table border="1" cellpadding="1" cellspacing="0" row_id="7948" txt_name="PRESTWICK RWY 02"><tr><td>552644N 0043643W -<br/>552657N 0043735W -<br/>552808N 0043640W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to<br/>552804N 0043541W -<br/>552644N 0043643W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6119638889,55.4454555556,609.6 -4.5946817778,55.4678045556,609.6 -4.6002036153,55.467927257,609.6 -4.605693511,55.4682859911,609.6 -4.6111202778,55.4688787222,609.6 -4.6264277778,55.4490722222,609.6 -4.6119638889,55.4454555556,609.6 + + + + + + EGRU504C PRESTWICK RWY 20 + <table border="1" cellpadding="1" cellspacing="0" row_id="8033" txt_name="PRESTWICK RWY 20"><tr><td>553247N 0043304W -<br/>553234N 0043212W -<br/>553215N 0043226W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to<br/>553237N 0043311W -<br/>553247N 0043304W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.551125,55.5462972222,609.6 -4.5531429722,55.5436986389,609.6 -4.548697861,55.5418268629,609.6 -4.5445148706,55.539770143,609.6 -4.5406178611,55.5375402222,609.6 -4.5366222222,55.5426833333,609.6 -4.551125,55.5462972222,609.6 + + + + + + EGRU504D PRESTWICK RWY 12 + <table border="1" cellpadding="1" cellspacing="0" row_id="7647" txt_name="PRESTWICK RWY 12"><tr><td>553205N 0044100W -<br/>553233N 0044030W -<br/>553205N 0043910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to<br/>553137N 0043939W -<br/>553205N 0044100W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.6832444444,55.534725,609.6 -4.6609490833,55.5270424444,609.6 -4.6585352738,55.5297116791,609.6 -4.655788149,55.5322752062,609.6 -4.6527219722,55.5347196667,609.6 -4.675,55.5423972222,609.6 -4.6832444444,55.534725,609.6 + + + + + + EGRU504E PRESTWICK RWY 30 + <table border="1" cellpadding="1" cellspacing="0" row_id="7729" txt_name="PRESTWICK RWY 30"><tr><td>552858N 0043010W -<br/>552831N 0043040W -<br/>552903N 0043211W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to<br/>552930N 0043142W -<br/>552858N 0043010W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5027611111,55.4828555556,609.6 -4.528274,55.4917018333,609.6 -4.5306940537,55.4890358972,609.6 -4.5334458761,55.4864758646,609.6 -4.5365151111,55.4840350278,609.6 -4.5109833333,55.4751833333,609.6 -4.5027611111,55.4828555556,609.6 + + + + + + EGRU505A GLASGOW + <table border="1" cellpadding="1" cellspacing="0" row_id="8168" txt_name="GLASGOW"><tr><td>A circle, 2.5 NM radius, centred at 555218N 0042601W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.4336611111,55.9133066058,609.6 -4.4404927814,55.9131290254,609.6 -4.4472659805,55.9125978039,609.6 -4.4539227421,55.911717488,609.6 -4.4604061061,55.9104956113,609.6 -4.4666606098,55.90894263,609.6 -4.4726327666,55.907071832,609.6 -4.4782715259,55.9048992227,609.6 -4.4835287129,55.9024433866,609.6 -4.4883594411,55.8997253273,609.6 -4.4927224969,55.8967682863,609.6 -4.4965806909,55.8935975433,609.6 -4.4999011742,55.8902401984,609.6 -4.5026557162,55.8867249395,609.6 -4.5048209421,55.883081796,609.6 -4.5063785279,55.8793418811,609.6 -4.5073153518,55.8755371254,609.6 -4.5076236004,55.8717000041,609.6 -4.5073008292,55.8678632586,609.6 -4.5063499773,55.8640596179,609.6 -4.5047793358,55.8603215189,609.6 -4.502602471,55.8566808305,609.6 -4.4998381033,55.8531685823,609.6 -4.496509942,55.8498147012,609.6 -4.4926464793,55.846647757,609.6 -4.4882807436,55.8436947207,609.6 -4.4834500153,55.8409807353,609.6 -4.4781955083,55.8385289038,609.6 -4.4725620176,55.8363600934,609.6 -4.4665975388,55.8344927591,609.6 -4.4603528607,55.8329427885,609.6 -4.4538811356,55.8317233669,609.6 -4.4472374298,55.8308448669,609.6 -4.4404782588,55.8303147604,609.6 -4.4336611111,55.8301375558,609.6 -4.4268439634,55.8303147604,609.6 -4.4200847924,55.8308448669,609.6 -4.4134410866,55.8317233669,609.6 -4.4069693615,55.8329427885,609.6 -4.4007246835,55.8344927591,609.6 -4.3947602046,55.8363600934,609.6 -4.3891267139,55.8385289038,609.6 -4.3838722069,55.8409807353,609.6 -4.3790414787,55.8436947207,609.6 -4.3746757429,55.846647757,609.6 -4.3708122802,55.8498147012,609.6 -4.367484119,55.8531685823,609.6 -4.3647197512,55.8566808305,609.6 -4.3625428864,55.8603215189,609.6 -4.3609722449,55.8640596179,609.6 -4.360021393,55.8678632586,609.6 -4.3596986219,55.8717000041,609.6 -4.3600068705,55.8755371254,609.6 -4.3609436943,55.8793418811,609.6 -4.3625012801,55.883081796,609.6 -4.364666506,55.8867249395,609.6 -4.367421048,55.8902401984,609.6 -4.3707415313,55.8935975433,609.6 -4.3745997254,55.8967682863,609.6 -4.3789627812,55.8997253273,609.6 -4.3837935094,55.9024433866,609.6 -4.3890506963,55.9048992227,609.6 -4.3946894557,55.907071832,609.6 -4.4006616124,55.90894263,609.6 -4.4069161161,55.9104956113,609.6 -4.4133994801,55.911717488,609.6 -4.4200562418,55.9125978039,609.6 -4.4268294408,55.9131290254,609.6 -4.4336611111,55.9133066058,609.6 + + + + + + EGRU505B GLASGOW RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8173" txt_name="GLASGOW RWY 05"><tr><td>554945N 0043005W -<br/>555009N 0043044W -<br/>555047N 0042933W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to<br/>555024N 0042853W -<br/>554945N 0043005W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.5013388889,55.8292444444,609.6 -4.4813740556,55.8399566111,609.6 -4.4853205407,55.8419728253,609.6 -4.4889988796,55.844143751,609.6 -4.4923899444,55.8464581111,609.6 -4.5123388889,55.8357527778,609.6 -4.5013388889,55.8292444444,609.6 + + + + + + EGRU505C GLASGOW RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7629" txt_name="GLASGOW RWY 23"><tr><td>555444N 0042210W -<br/>555421N 0042130W -<br/>555349N 0042229W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to<br/>555412N 0042309W -<br/>555444N 0042210W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.3693777778,55.9122694444,609.6 -4.3858671944,55.9034677222,609.6 -4.3819197029,55.9014481405,609.6 -4.3782420207,55.8992738431,609.6 -4.3748532778,55.8969561667,609.6 -4.35835,55.9057638889,609.6 -4.3693777778,55.9122694444,609.6 + + + + + + EGRU506A CUMBERNAULD + <table border="1" cellpadding="1" cellspacing="0" row_id="7652" txt_name="CUMBERNAULD"><tr><td>A circle, 2 NM radius, centred at 555829N 0035832W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9754333333,56.0079225256,609.6 -3.9815386102,56.0077460559,609.6 -3.9875790042,56.0072185223,609.6 -3.9934903273,56.0063455309,609.6 -3.9992097732,56.0051363583,609.6 -4.0046765897,56.0036038528,609.6 -4.0098327274,56.0017642963,609.6 -4.0146234598,55.9996372304,609.6 -4.0189979659,55.9972452479,609.6 -4.0229098711,55.9946137503,609.6 -4.026317738,55.991770678,609.6 -4.0291855056,55.9887462108,609.6 -4.0314828677,55.9855724473,609.6 -4.0331855908,55.9822830623,609.6 -4.0342757661,55.978912949,609.6 -4.0347419927,55.9754978476,609.6 -4.0345794927,55.9720739659,609.6 -4.0337901541,55.9686775956,609.6 -4.0323825044,55.9653447272,609.6 -4.0303716132,55.9621106691,609.6 -4.0277789261,55.9590096745,609.6 -4.0246320321,55.9560745792,609.6 -4.0209643667,55.953336455,609.6 -4.0168148538,55.9508242826,609.6 -4.012227492,55.9485646454,609.6 -4.0072508868,55.9465814505,609.6 -4.0019377369,55.9448956766,609.6 -3.9963442776,55.9435251539,609.6 -3.9905296883,55.9424843764,609.6 -3.9845554704,55.9417843499,609.6 -3.9784848002,55.9414324764,609.6 -3.9723818665,55.9414324764,609.6 -3.9663111963,55.9417843499,609.6 -3.9603369783,55.9424843764,609.6 -3.9545223891,55.9435251539,609.6 -3.9489289298,55.9448956766,609.6 -3.9436157799,55.9465814505,609.6 -3.9386391747,55.9485646454,609.6 -3.9340518128,55.9508242826,609.6 -3.9299023,55.953336455,609.6 -3.9262346345,55.9560745792,609.6 -3.9230877405,55.9590096745,609.6 -3.9204950535,55.9621106691,609.6 -3.9184841622,55.9653447272,609.6 -3.9170765126,55.9686775956,609.6 -3.916287174,55.9720739659,609.6 -3.9161246739,55.9754978476,609.6 -3.9165909006,55.978912949,609.6 -3.9176810758,55.9822830623,609.6 -3.919383799,55.9855724473,609.6 -3.9216811611,55.9887462108,609.6 -3.9245489286,55.991770678,609.6 -3.9279567956,55.9946137503,609.6 -3.9318687007,55.9972452479,609.6 -3.9362432069,55.9996372304,609.6 -3.9410339393,56.0017642963,609.6 -3.946190077,56.0036038528,609.6 -3.9516568934,56.0051363583,609.6 -3.9573763394,56.0063455309,609.6 -3.9632876624,56.0072185223,609.6 -3.9693280564,56.0077460559,609.6 -3.9754333333,56.0079225256,609.6 + + + + + + EGRU506B CUMBERNAULD RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7856" txt_name="CUMBERNAULD RWY 07"><tr><td>555721N 0040320W -<br/>555752N 0040338W -<br/>555809N 0040202W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to<br/>555738N 0040145W -<br/>555721N 0040320W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0556527778,55.9557666667,609.6 -4.0290868333,55.9604704167,609.6 -4.031149962,55.9632401287,609.6 -4.0327598646,55.9661028542,609.6 -4.0339033333,55.9690353056,609.6 -4.0604583333,55.9643333333,609.6 -4.0556527778,55.9557666667,609.6 + + + + + + EGRU506C CUMBERNAULD RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7836" txt_name="CUMBERNAULD RWY 25"><tr><td>555937N 0035343W -<br/>555906N 0035325W -<br/>555849N 0035501W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to<br/>555920N 0035518W -<br/>555937N 0035343W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.8951527778,55.9934916667,609.6 -3.9217423611,55.9888194444,609.6 -3.9196852867,55.9860479238,609.6 -3.9180825215,55.9831837186,609.6 -3.9169470278,55.9802501667,609.6 -3.8903416667,55.984925,609.6 -3.8951527778,55.9934916667,609.6 + + + + + + EGRU507A EDINBURGH + <table border="1" cellpadding="1" cellspacing="0" row_id="7634" txt_name="EDINBURGH"><tr><td>A circle, 2.5 NM radius, centred at 555700N 0032221W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3725,55.9915838517,609.6 -3.3793454676,55.991406273,609.6 -3.3861323453,55.9908750567,609.6 -3.3928025494,55.9899947493,609.6 -3.399299004,55.9887728846,609.6 -3.4055661343,55.9872199186,609.6 -3.411550345,55.9853491394,609.6 -3.4172004825,55.9831765523,609.6 -3.4224682743,55.9807207417,609.6 -3.4273087435,55.9780027111,609.6 -3.4316805932,55.975045702,609.6 -3.4355465594,55.9718749939,609.6 -3.438873727,55.9685176868,609.6 -3.4416338089,55.9650024685,609.6 -3.4438033837,55.9613593679,609.6 -3.445364091,55.9576194981,609.6 -3.4463027832,55.9538147896,609.6 -3.446611632,55.9499777168,609.6 -3.4462881886,55.946141021,609.6 -3.4453353986,55.9423374306,609.6 -3.4437615707,55.9385993821,609.6 -3.4415802993,55.9349587439,609.6 -3.4388103428,55.9314465451,609.6 -3.4354754592,55.9280927121,609.6 -3.4316041982,55.9249258141,609.6 -3.4272296552,55.9219728214,609.6 -3.422389186,55.9192588768,609.6 -3.4171240874,55.9168070827,609.6 -3.4114792447,55.9146383056,609.6 -3.40550275,55.9127710004,609.6 -3.3992454943,55.9112210541,609.6 -3.3927607363,55.9100016517,609.6 -3.3861036529,55.9091231656,609.6 -3.3793308729,55.9085930675,609.6 -3.3725,55.9084158658,609.6 -3.3656691271,55.9085930675,609.6 -3.3588963471,55.9091231656,609.6 -3.3522392637,55.9100016517,609.6 -3.3457545057,55.9112210541,609.6 -3.33949725,55.9127710004,609.6 -3.3335207553,55.9146383056,609.6 -3.3278759126,55.9168070827,609.6 -3.322610814,55.9192588768,609.6 -3.3177703448,55.9219728214,609.6 -3.3133958018,55.9249258141,609.6 -3.3095245408,55.9280927121,609.6 -3.3061896572,55.9314465451,609.6 -3.3034197007,55.9349587439,609.6 -3.3012384293,55.9385993821,609.6 -3.2996646014,55.9423374306,609.6 -3.2987118114,55.946141021,609.6 -3.298388368,55.9499777168,609.6 -3.2986972168,55.9538147896,609.6 -3.299635909,55.9576194981,609.6 -3.3011966163,55.9613593679,609.6 -3.3033661911,55.9650024685,609.6 -3.306126273,55.9685176868,609.6 -3.3094534406,55.9718749939,609.6 -3.3133194068,55.975045702,609.6 -3.3176912565,55.9780027111,609.6 -3.3225317257,55.9807207417,609.6 -3.3277995175,55.9831765523,609.6 -3.333449655,55.9853491394,609.6 -3.3394338657,55.9872199186,609.6 -3.345700996,55.9887728846,609.6 -3.3521974506,55.9899947493,609.6 -3.3588676547,55.9908750567,609.6 -3.3656545324,55.991406273,609.6 -3.3725,55.9915838517,609.6 + + + + + + EGRU507B EDINBURGH RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8058" txt_name="EDINBURGH RWY 06"><tr><td>555504N 0032705W -<br/>555532N 0032735W -<br/>555557N 0032623W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to<br/>555529N 0032553W -<br/>555504N 0032705W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4515083333,55.9179055556,609.6 -3.4313687778,55.9247520556,609.6 -3.4344587671,55.9271983849,609.6 -3.4372270503,55.9297633256,609.6 -3.4396591944,55.9324335556,609.6 -3.459775,55.9255944444,609.6 -3.4515083333,55.9179055556,609.6 + + + + + + EGRU507C EDINBURGH RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7546" txt_name="EDINBURGH RWY 24"><tr><td>555855N 0031737W -<br/>555827N 0031707W -<br/>555803N 0031819W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to<br/>555831N 0031849W -<br/>555855N 0031737W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2935388889,55.9819416667,609.6 -3.3135155278,55.9751909167,609.6 -3.3104327879,55.9727397804,609.6 -3.3076735423,55.970170342,609.6 -3.3052520833,55.967496,609.6 -3.2852555556,55.9742527778,609.6 -3.2935388889,55.9819416667,609.6 + + + + + + EGRU508A NEWCASTLE + <table border="1" cellpadding="1" cellspacing="0" row_id="8167" txt_name="NEWCASTLE"><tr><td>A circle, 2.5 NM radius, centred at 550217N 0014123W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6898111111,55.0795123069,609.6 -1.6964999664,55.0793347079,609.6 -1.7031315782,55.0788034309,609.6 -1.7096491977,55.0779230223,609.6 -1.7159970603,55.0767010161,609.6 -1.7221208669,55.0751478684,609.6 -1.7279682522,55.0732768675,609.6 -1.7334892353,55.071104019,609.6 -1.7386366495,55.0686479081,609.6 -1.7433665467,55.065929539,609.6 -1.7476385734,55.0629721544,609.6 -1.7514163152,55.0598010353,609.6 -1.754667606,55.0564432835,609.6 -1.7573648005,55.0529275891,609.6 -1.7594850068,55.0492839838,609.6 -1.7610102773,55.0455435839,609.6 -1.7619277575,55.0417383236,609.6 -1.7622297899,55.0379006818,609.6 -1.7619139737,55.0340634042,609.6 -1.760983179,55.0302592245,609.6 -1.7594455168,55.0265205847,609.6 -1.7573142637,55.022879359,609.6 -1.7546077433,55.0193665826,609.6 -1.7513491651,55.016012188,609.6 -1.7475664227,55.0128447508,609.6 -1.7432918523,55.0098912476,609.6 -1.7385619551,55.0071768272,609.6 -1.7334170845,55.0047245977,609.6 -1.727901102,55.0025554312,609.6 -1.7220610041,55.0006877874,609.6 -1.7159465234,54.9991375578,609.6 -1.7096097077,54.9979179311,609.6 -1.7031044799,54.9970392826,609.6 -1.6964861825,54.9965090862,609.6 -1.6898111111,54.9963318516,609.6 -1.6831360397,54.9965090862,609.6 -1.6765177423,54.9970392826,609.6 -1.6700125145,54.9979179311,609.6 -1.6636756989,54.9991375578,609.6 -1.6575612182,55.0006877874,609.6 -1.6517211202,55.0025554312,609.6 -1.6462051377,55.0047245977,609.6 -1.6410602671,55.0071768272,609.6 -1.6363303699,55.0098912476,609.6 -1.6320557995,55.0128447508,609.6 -1.6282730571,55.016012188,609.6 -1.6250144789,55.0193665826,609.6 -1.6223079585,55.022879359,609.6 -1.6201767054,55.0265205847,609.6 -1.6186390432,55.0302592245,609.6 -1.6177082486,55.0340634042,609.6 -1.6173924323,55.0379006818,609.6 -1.6176944647,55.0417383236,609.6 -1.6186119449,55.0455435839,609.6 -1.6201372155,55.0492839838,609.6 -1.6222574217,55.0529275891,609.6 -1.6249546162,55.0564432835,609.6 -1.628205907,55.0598010353,609.6 -1.6319836488,55.0629721544,609.6 -1.6362556755,55.065929539,609.6 -1.6409855727,55.0686479081,609.6 -1.6461329869,55.071104019,609.6 -1.6516539701,55.0732768675,609.6 -1.6575013554,55.0751478684,609.6 -1.6636251619,55.0767010161,609.6 -1.6699730245,55.0779230223,609.6 -1.676490644,55.0788034309,609.6 -1.6831222558,55.0793347079,609.6 -1.6898111111,55.0795123069,609.6 + + + + + + EGRU508B NEWCASTLE RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="7673" txt_name="NEWCASTLE RWY 07"><tr><td>550040N 0014620W -<br/>550109N 0014644W -<br/>550129N 0014530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to<br/>550059N 0014507W -<br/>550040N 0014620W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.7723027778,55.0110388889,609.6 -1.7518513611,55.0164843056,609.6 -1.7543812399,55.0191080779,609.6 -1.7565757289,55.0218297539,609.6 -1.7584233611,55.0246351944,609.6 -1.7788555556,55.0191944444,609.6 -1.7723027778,55.0110388889,609.6 + + + + + + EGRU508C NEWCASTLE RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="8093" txt_name="NEWCASTLE RWY 25"><tr><td>550353N 0013627W -<br/>550324N 0013603W -<br/>550304N 0013716W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to<br/>550334N 0013740W -<br/>550353N 0013627W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6074555556,55.0646833333,609.6 -1.6277036667,55.0593275,609.6 -1.6251793523,55.0567007126,609.6 -1.622991767,55.05397627,609.6 -1.62115225,55.0511683611,609.6 -1.6008888889,55.0565277778,609.6 -1.6074555556,55.0646833333,609.6 + + + + + + EGRU509A KIRKNEWTON + <table border="1" cellpadding="1" cellspacing="0" row_id="8504" txt_name="KIRKNEWTON"><tr><td>A circle, 2 NM radius, centred at 555224N 0032355W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.398525,55.906473077,609.6 -3.4046143306,55.906296605,609.6 -3.4106389485,55.9057690643,609.6 -3.4165348337,55.9048960612,609.6 -3.4222393447,55.9036868723,609.6 -3.4276918883,55.9021543458,609.6 -3.4328345671,55.9003147639,609.6 -3.4376127976,55.8981876682,609.6 -3.4419758918,55.8957956516,609.6 -3.4458775957,55.8931641159,609.6 -3.4492765804,55.8903210016,609.6 -3.452136878,55.8872964889,609.6 -3.4544282614,55.8841226767,609.6 -3.4561265595,55.8808332402,609.6 -3.4572139095,55.877463073,609.6 -3.4576789395,55.8740479158,609.6 -3.4575168832,55.8706239771,609.6 -3.4567296229,55.867227549,609.6 -3.4553256631,55.8638946228,609.6 -3.4533200331,55.8606605077,609.6 -3.450734122,55.8575594574,609.6 -3.4475954465,55.8546243084,609.6 -3.4439373541,55.8518861335,609.6 -3.4397986674,55.8493739138,609.6 -3.4352232698,55.8471142336,609.6 -3.4302596402,55.8451310006,609.6 -3.4249603402,55.843445194,609.6 -3.4193814587,55.8420746444,609.6 -3.4135820215,55.8410338464,609.6 -3.40762337,55.8403338061,609.6 -3.4015685166,55.8399819256,609.6 -3.3954814834,55.8399819256,609.6 -3.38942663,55.8403338061,609.6 -3.3834679785,55.8410338464,609.6 -3.3776685413,55.8420746444,609.6 -3.3720896598,55.843445194,609.6 -3.3667903598,55.8451310006,609.6 -3.3618267302,55.8471142336,609.6 -3.3572513326,55.8493739138,609.6 -3.3531126459,55.8518861335,609.6 -3.3494545535,55.8546243084,609.6 -3.346315878,55.8575594574,609.6 -3.3437299669,55.8606605077,609.6 -3.3417243369,55.8638946228,609.6 -3.3403203771,55.867227549,609.6 -3.3395331168,55.8706239771,609.6 -3.3393710605,55.8740479158,609.6 -3.3398360905,55.877463073,609.6 -3.3409234405,55.8808332402,609.6 -3.3426217386,55.8841226767,609.6 -3.344913122,55.8872964889,609.6 -3.3477734196,55.8903210016,609.6 -3.3511724043,55.8931641159,609.6 -3.3550741082,55.8957956516,609.6 -3.3594372024,55.8981876682,609.6 -3.3642154329,55.9003147639,609.6 -3.3693581117,55.9021543458,609.6 -3.3748106553,55.9036868723,609.6 -3.3805151663,55.9048960612,609.6 -3.3864110515,55.9057690643,609.6 -3.3924356694,55.906296605,609.6 -3.398525,55.906473077,609.6 + + + + + + EGRU510 HMP NORTHUMBERLAND + <table border="1" cellpadding="1" cellspacing="0" row_id="14142" txt_name="HMP NORTHUMBERLAND"><tr><td>551818N 0013757W -<br/>551756N 0013719W -<br/>551743N 0013716W -<br/>551716N 0013805W -<br/>551720N 0013839W -<br/>551737N 0013910W -<br/>551818N 0013757W <br/>Upper limit: 600 FT MSL<br/>Lower limit: SFC <br/>Class: </td><td>HMP Restricted airspace active H24.<br/>Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.<br/>HMPPS email: drone.RFZapplication@justice.gov.uk<br/>SI 2023/1101<br/>Site elevation: 118 FT AMSL</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6326027778,55.3049305556,182.88 -1.6528194444,55.2935,182.88 -1.6441694444,55.2888166667,182.88 -1.63475,55.2877805556,182.88 -1.6210055556,55.2953416667,182.88 -1.6220055556,55.2989555556,182.88 -1.6326027778,55.3049305556,182.88 + + + + + + EGRU601A TIREE + <table border="1" cellpadding="1" cellspacing="0" row_id="7964" txt_name="TIREE"><tr><td>A circle, 2 NM radius, centred at 562957N 0065209W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.8691666667,56.5324307986,609.6 -6.8753560547,56.5322543409,609.6 -6.8814796627,56.5317268434,609.6 -6.8874724149,56.5308539119,609.6 -6.8932706372,56.5296448231,609.6 -6.898812738,56.5281124248,609.6 -6.9040398665,56.5262729986,609.6 -6.9088965412,56.5241460857,609.6 -6.9133312409,56.5217542778,609.6 -6.9172969527,56.5191229759,609.6 -6.92075167,56.5162801189,609.6 -6.9236588372,56.5132558855,609.6 -6.9259877337,56.5100823723,609.6 -6.9277137958,56.5067932523,609.6 -6.928818872,56.5034234163,609.6 -6.9292914089,56.5000086018,609.6 -6.929126567,56.4965850139,609.6 -6.9283262651,56.4931889409,609.6 -6.9268991521,56.4898563701,609.6 -6.9248605091,56.4866226063,609.6 -6.9222320802,56.4835218989,609.6 -6.9190418369,56.4805870799,609.6 -6.9153236767,56.4778492177,609.6 -6.9111170607,56.4753372889,609.6 -6.9064665928,56.4730778737,609.6 -6.901421547,56.4710948757,609.6 -6.8960353454,56.4694092709,609.6 -6.8903649949,56.4680388867,609.6 -6.8844704862,56.466998215,609.6 -6.8784141631,56.46629826,609.6 -6.8722600672,56.4659464225,609.6 -6.8660732661,56.4659464225,609.6 -6.8599191702,56.46629826,609.6 -6.8538628471,56.466998215,609.6 -6.8479683384,56.4680388867,609.6 -6.8422979879,56.4694092709,609.6 -6.8369117864,56.4710948757,609.6 -6.8318667405,56.4730778737,609.6 -6.8272162726,56.4753372889,609.6 -6.8230096566,56.4778492177,609.6 -6.8192914965,56.4805870799,609.6 -6.8161012532,56.4835218989,609.6 -6.8134728243,56.4866226063,609.6 -6.8114341812,56.4898563701,609.6 -6.8100070682,56.4931889409,609.6 -6.8092067663,56.4965850139,609.6 -6.8090419244,56.5000086018,609.6 -6.8095144613,56.5034234163,609.6 -6.8106195375,56.5067932523,609.6 -6.8123455996,56.5100823723,609.6 -6.8146744961,56.5132558855,609.6 -6.8175816633,56.5162801189,609.6 -6.8210363807,56.5191229759,609.6 -6.8250020924,56.5217542778,609.6 -6.8294367922,56.5241460857,609.6 -6.8342934669,56.5262729986,609.6 -6.8395205953,56.5281124248,609.6 -6.8450626961,56.5296448231,609.6 -6.8508609184,56.5308539119,609.6 -6.8568536707,56.5317268434,609.6 -6.8629772786,56.5322543409,609.6 -6.8691666667,56.5324307986,609.6 + + + + + + EGRU601B TIREE RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="7705" txt_name="TIREE RWY 05"><tr><td>562739N 0065554W -<br/>562803N 0065634W -<br/>562848N 0065506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to<br/>562824N 0065426W -<br/>562739N 0065554W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.9317583333,56.4608361111,609.6 -6.9072867778,56.47344325,609.6 -6.9113222392,56.4754483478,609.6 -6.9150151454,56.477646477,609.6 -6.9183354167,56.4800197778,609.6 -6.9428,56.4674138889,609.6 -6.9317583333,56.4608361111,609.6 + + + + + + EGRU601C TIREE RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7885" txt_name="TIREE RWY 23"><tr><td>563213N 0064828W -<br/>563149N 0064748W -<br/>563106N 0064912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to<br/>563130N 0064952W -<br/>563213N 0064828W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.8076972222,56.5368638889,609.6 -6.83103425,56.5248960833,609.6 -6.8269941803,56.5228900067,609.6 -6.8232981894,56.5206906729,609.6 -6.8199763611,56.5183160278,609.6 -6.7966305556,56.5302861111,609.6 -6.8076972222,56.5368638889,609.6 + + + + + + EGRU601D TIREE RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="8127" txt_name="TIREE RWY 11"><tr><td>563040N 0065734W -<br/>563111N 0065716W -<br/>563051N 0065522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to<br/>563021N 0065541W -<br/>563040N 0065734W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.9593305556,56.5110166667,609.6 -6.9281294444,56.5057391389,609.6 -6.9268188412,56.5086545573,609.6 -6.9250376557,56.5114926778,609.6 -6.9228003333,56.5142303333,609.6 -6.9545611111,56.5196027778,609.6 -6.9593305556,56.5110166667,609.6 + + + + + + EGRU601E TIREE RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="7580" txt_name="TIREE RWY 29"><tr><td>562928N 0064712W -<br/>562857N 0064730W -<br/>562911N 0064849W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to<br/>562942N 0064834W -<br/>562928N 0064712W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.7867861111,56.4911138889,609.6 -6.80950325,56.4949871389,609.6 -6.8104304407,56.4920271763,609.6 -6.8118364249,56.4891255438,609.6 -6.8137096111,56.4863058889,609.6 -6.79155,56.4825277778,609.6 -6.7867861111,56.4911138889,609.6 + + + + + + EGRU602A COLL + <table border="1" cellpadding="1" cellspacing="0" row_id="8042" txt_name="COLL"><tr><td>A circle, 2 NM radius, centred at 563607N 0063704W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.6177444444,56.6353302443,609.6 -6.6239506685,56.635153789,609.6 -6.6300909328,56.6346262985,609.6 -6.6360999842,56.6337533787,609.6 -6.6419139746,56.6325443062,609.6 -6.6474711444,56.6310119287,609.6 -6.6527124825,56.6291725279,609.6 -6.6575823563,56.6270456447,609.6 -6.6620291044,56.6246538708,609.6 -6.6660055861,56.622022607,609.6 -6.6694696809,56.6191797919,609.6 -6.6723847342,56.616155604,609.6 -6.6747199424,56.6129821396,609.6 -6.6764506758,56.6096930713,609.6 -6.6775587344,56.6063232894,609.6 -6.678032534,56.6029085309,609.6 -6.6778672232,56.5994850003,609.6 -6.6770647265,56.5960889855,609.6 -6.6756337175,56.5927564728,609.6 -6.6735895195,56.5895227666,609.6 -6.6709539363,56.5864221154,609.6 -6.6677550161,56.5834873505,609.6 -6.6640267488,56.5807495395,609.6 -6.659808703,56.5782376584,609.6 -6.6551456038,56.5759782867,609.6 -6.650086859,56.5739953273,609.6 -6.6446860355,56.5723097556,609.6 -6.6390002947,56.5709393985,609.6 -6.6330897895,56.5698987475,609.6 -6.6270170324,56.5691988065,609.6 -6.6208462383,56.5688469761,609.6 -6.6146426506,56.5688469761,609.6 -6.6084718565,56.5691988065,609.6 -6.6023990994,56.5698987475,609.6 -6.5964885942,56.5709393985,609.6 -6.5908028534,56.5723097556,609.6 -6.5854020299,56.5739953273,609.6 -6.5803432851,56.5759782867,609.6 -6.5756801859,56.5782376584,609.6 -6.5714621401,56.5807495395,609.6 -6.5677338728,56.5834873505,609.6 -6.5645349526,56.5864221154,609.6 -6.5618993694,56.5895227666,609.6 -6.5598551714,56.5927564728,609.6 -6.5584241624,56.5960889855,609.6 -6.5576216657,56.5994850003,609.6 -6.5574563549,56.6029085309,609.6 -6.5579301545,56.6063232894,609.6 -6.559038213,56.6096930713,609.6 -6.5607689465,56.6129821396,609.6 -6.5631041547,56.616155604,609.6 -6.566019208,56.6191797919,609.6 -6.5694833028,56.622022607,609.6 -6.5734597845,56.6246538708,609.6 -6.5779065326,56.6270456447,609.6 -6.5827764064,56.6291725279,609.6 -6.5880177445,56.6310119287,609.6 -6.5935749143,56.6325443062,609.6 -6.5993889047,56.6337533787,609.6 -6.6053979561,56.6346262985,609.6 -6.6115382204,56.635153789,609.6 -6.6177444444,56.6353302443,609.6 + + + + + + EGRU603A COLONSAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7713" txt_name="COLONSAY"><tr><td>A circle, 2 NM radius, centred at 560327N 0061435W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2430777778,56.0908304089,609.6 -6.2491961631,56.0906539411,609.6 -6.2552495257,56.0901264132,609.6 -6.2611735392,56.0892534313,609.6 -6.2669052621,56.0880442721,609.6 -6.2723838114,56.0865117836,609.6 -6.2775510128,56.0846722478,609.6 -6.2823520222,56.0825452064,609.6 -6.2867359094,56.0801532515,609.6 -6.2906562002,56.0775217851,609.6 -6.2940713687,56.0746787469,609.6 -6.2969452767,56.0716543169,609.6 -6.2992475535,56.0684805931,609.6 -6.3009539141,56.0651912502,609.6 -6.3020464118,56.0618211809,609.6 -6.302513622,56.058406125,609.6 -6.3023507571,56.0549822899,609.6 -6.3015597101,56.0515859667,609.6 -6.3001490272,56.0482531455,609.6 -6.2981338111,56.045019134,609.6 -6.2955355538,56.0419181849,609.6 -6.2923819039,56.0389831333,609.6 -6.288706369,56.0362450506,609.6 -6.2845479568,56.0337329167,609.6 -6.27995076,56.0314733147,609.6 -6.2749634884,56.029490151,609.6 -6.2696389535,56.0278044039,609.6 -6.2640335107,56.0264339031,609.6 -6.2582064661,56.0253931423,609.6 -6.252219452,56.0246931271,609.6 -6.24613578,56.0243412593,609.6 -6.2400197755,56.0243412593,609.6 -6.2339361035,56.0246931271,609.6 -6.2279490895,56.0253931423,609.6 -6.2221220449,56.0264339031,609.6 -6.2165166021,56.0278044039,609.6 -6.2111920672,56.029490151,609.6 -6.2062047956,56.0314733147,609.6 -6.2016075988,56.0337329167,609.6 -6.1974491865,56.0362450506,609.6 -6.1937736516,56.0389831333,609.6 -6.1906200018,56.0419181849,609.6 -6.1880217445,56.045019134,609.6 -6.1860065283,56.0482531455,609.6 -6.1845958455,56.0515859667,609.6 -6.1838047984,56.0549822899,609.6 -6.1836419335,56.058406125,609.6 -6.1841091438,56.0618211809,609.6 -6.1852016415,56.0651912502,609.6 -6.1869080021,56.0684805931,609.6 -6.1892102788,56.0716543169,609.6 -6.1920841868,56.0746787469,609.6 -6.1954993554,56.0775217851,609.6 -6.1994196462,56.0801532515,609.6 -6.2038035334,56.0825452064,609.6 -6.2086045427,56.0846722478,609.6 -6.2137717441,56.0865117836,609.6 -6.2192502934,56.0880442721,609.6 -6.2249820164,56.0892534313,609.6 -6.2309060299,56.0901264132,609.6 -6.2369593925,56.0906539411,609.6 -6.2430777778,56.0908304089,609.6 + + + + + + EGRU604A OBAN + <table border="1" cellpadding="1" cellspacing="0" row_id="8134" txt_name="OBAN"><tr><td>A circle, 2 NM radius, centred at 562749N 0052400W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3998638889,56.4969837675,609.6 -5.406047503,56.496807309,609.6 -5.4121653987,56.4962798091,609.6 -5.4181525612,56.4954068736,609.6 -5.4239453758,56.4941977792,609.6 -5.4294823086,56.4926653737,609.6 -5.4347045639,56.4908259387,609.6 -5.439556712,56.4886990155,609.6 -5.4439872797,56.4863071959,609.6 -5.4479492979,56.4836758809,609.6 -5.4514007993,56.4808330094,609.6 -5.4543052619,56.4778087602,609.6 -5.4566319937,56.4746352302,609.6 -5.4583564538,56.4713460924,609.6 -5.4594605072,56.4679762377,609.6 -5.459932611,56.4645614039,609.6 -5.45976793,56.4611377962,609.6 -5.4589683807,56.4577417032,609.6 -5.4575426038,56.4544091123,609.6 -5.4555058658,56.4511753287,609.6 -5.4528798905,56.4480746019,609.6 -5.4496926229,56.4451397644,609.6 -5.445977929,56.4424018844,609.6 -5.4417752329,56.4398899392,609.6 -5.4371290969,56.437630509,609.6 -5.4320887491,56.4356474978,609.6 -5.4267075622,56.4339618815,609.6 -5.4210424898,56.432591488,609.6 -5.4151534672,56.4315508091,609.6 -5.4091027801,56.4308508493,609.6 -5.4029544109,56.4304990094,609.6 -5.3967733668,56.4304990094,609.6 -5.3906249977,56.4308508493,609.6 -5.3845743106,56.4315508091,609.6 -5.3786852879,56.432591488,609.6 -5.3730202156,56.4339618815,609.6 -5.3676390286,56.4356474978,609.6 -5.3625986809,56.437630509,609.6 -5.3579525449,56.4398899392,609.6 -5.3537498487,56.4424018844,609.6 -5.3500351548,56.4451397644,609.6 -5.3468478873,56.4480746019,609.6 -5.3442219119,56.4511753287,609.6 -5.342185174,56.4544091123,609.6 -5.3407593971,56.4577417032,609.6 -5.3399598478,56.4611377962,609.6 -5.3397951668,56.4645614039,609.6 -5.3402672706,56.4679762377,609.6 -5.341371324,56.4713460924,609.6 -5.3430957841,56.4746352302,609.6 -5.3454225159,56.4778087602,609.6 -5.3483269785,56.4808330094,609.6 -5.3517784799,56.4836758809,609.6 -5.3557404981,56.4863071959,609.6 -5.3601710658,56.4886990155,609.6 -5.3650232139,56.4908259387,609.6 -5.3702454692,56.4926653737,609.6 -5.375782402,56.4941977792,609.6 -5.3815752166,56.4954068736,609.6 -5.3875623791,56.4962798091,609.6 -5.3936802747,56.496807309,609.6 -5.3998638889,56.4969837675,609.6 + + + + + + EGRU604B OBAN RWY 01 + <table border="1" cellpadding="1" cellspacing="0" row_id="7846" txt_name="OBAN RWY 01"><tr><td>562451N 0052402W -<br/>562454N 0052500W -<br/>562553N 0052449W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to<br/>562550N 0052351W -<br/>562451N 0052402W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.4004833333,56.4140361111,609.6 -5.3975838056,56.4304789167,609.6 -5.4030012099,56.4305003651,609.6 -5.4083931319,56.4307920761,609.6 -5.4137157778,56.4313516944,609.6 -5.4166083333,56.4149083333,609.6 -5.4004833333,56.4140361111,609.6 + + + + + + EGRU604C OBAN RWY 19 + <table border="1" cellpadding="1" cellspacing="0" row_id="7698" txt_name="OBAN RWY 19"><tr><td>563046N 0052358W -<br/>563043N 0052300W -<br/>562946N 0052310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to<br/>562949N 0052408W -<br/>563046N 0052358W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-5.3993666667,56.5127111111,609.6 -5.4021495278,56.4969597222,609.6 -5.3967225023,56.4969383259,609.6 -5.3913211261,56.4966461693,609.6 -5.3859895,56.4960856389,609.6 -5.3832,56.5118361111,609.6 -5.3993666667,56.5127111111,609.6 + + + + + + EGRU605A PERTH/SCONE + <table border="1" cellpadding="1" cellspacing="0" row_id="7697" txt_name="PERTH/SCONE"><tr><td>A circle, 2 NM radius, centred at 562628N 0032226W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3739055556,56.4743894449,609.6 -3.3800854962,56.4742129859,609.6 -3.3861997576,56.4736854844,609.6 -3.3921833637,56.4728125464,609.6 -3.3979727379,56.4716034484,609.6 -3.4035063827,56.4700710383,609.6 -3.4087255376,56.4682315978,609.6 -3.4135748057,56.466104668,609.6 -3.4180027446,56.4637128409,609.6 -3.4219624129,56.4610815175,609.6 -3.4254118681,56.4582386368,609.6 -3.42831461,56.4552143776,609.6 -3.4306399647,56.4520408369,609.6 -3.4323634055,56.4487516877,609.6 -3.4334668082,56.4453818211,609.6 -3.4339386364,56.4419669749,609.6 -3.4337740577,56.4385433546,609.6 -3.4329749872,56.4351472489,609.6 -3.4315500604,56.4318146452,609.6 -3.4295145345,56.4285808489,609.6 -3.4268901202,56.4254801098,609.6 -3.4237047459,56.4225452604,609.6 -3.4199922572,56.4198073692,609.6 -3.415792055,56.4172954134,609.6 -3.4111486751,56.4150359737,609.6 -3.4061113164,56.413052954,609.6 -3.4007333198,56.4113673305,609.6 -3.3950716055,56.409996931,609.6 -3.3891860732,56.4089562476,609.6 -3.3831389719,56.4082562846,609.6 -3.3769942462,56.4079044432,609.6 -3.3708168649,56.4079044432,609.6 -3.3646721392,56.4082562846,609.6 -3.3586250379,56.4089562476,609.6 -3.3527395056,56.409996931,609.6 -3.3470777913,56.4113673305,609.6 -3.3416997947,56.413052954,609.6 -3.336662436,56.4150359737,609.6 -3.3320190561,56.4172954134,609.6 -3.3278188539,56.4198073692,609.6 -3.3241063652,56.4225452604,609.6 -3.3209209909,56.4254801098,609.6 -3.3182965766,56.4285808489,609.6 -3.3162610507,56.4318146452,609.6 -3.3148361239,56.4351472489,609.6 -3.3140370534,56.4385433546,609.6 -3.3138724747,56.4419669749,609.6 -3.314344303,56.4453818211,609.6 -3.3154477056,56.4487516877,609.6 -3.3171711464,56.4520408369,609.6 -3.3194965011,56.4552143776,609.6 -3.322399243,56.4582386368,609.6 -3.3258486983,56.4610815175,609.6 -3.3298083665,56.4637128409,609.6 -3.3342363054,56.466104668,609.6 -3.3390855735,56.4682315978,609.6 -3.3443047284,56.4700710383,609.6 -3.3498383732,56.4716034484,609.6 -3.3556277474,56.4728125464,609.6 -3.3616113535,56.4736854844,609.6 -3.3677256149,56.4742129859,609.6 -3.3739055556,56.4743894449,609.6 + + + + + + EGRU605B PERTH/SCONE RWY 03 + <table border="1" cellpadding="1" cellspacing="0" row_id="8045" txt_name="PERTH/SCONE RWY 03"><tr><td>562346N 0032431W -<br/>562401N 0032522W -<br/>562451N 0032433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562436N 0032342W -<br/>562346N 0032431W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4084972222,56.3960916667,609.6 -3.3949996667,56.4099819444,609.6 -3.3999783657,56.4111619804,609.6 -3.4047452434,56.4125858503,609.6 -3.4092615556,56.4142419722,609.6 -3.42275,56.4003555556,609.6 -3.4084972222,56.3960916667,609.6 + + + + + + EGRU605C PERTH/SCONE RWY 21 + <table border="1" cellpadding="1" cellspacing="0" row_id="7578" txt_name="PERTH/SCONE RWY 21"><tr><td>562910N 0032021W -<br/>562855N 0031930W -<br/>562805N 0032019W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562820N 0032110W -<br/>562910N 0032021W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3392388889,56.4861444444,609.6 -3.3527793333,56.4722648056,609.6 -3.3477937836,56.4710829467,609.6 -3.3430213946,56.4696569316,609.6 -3.3385010833,56.4679984167,609.6 -3.3249527778,56.4818805556,609.6 -3.3392388889,56.4861444444,609.6 + + + + + + EGRU605D PERTH/SCONE RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8176" txt_name="PERTH/SCONE RWY 09"><tr><td>562554N 0032720W -<br/>562627N 0032721W -<br/>562628N 0032602W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562556N 0032554W -<br/>562554N 0032720W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4554361111,56.4317694444,609.6 -3.4317364167,56.4321758611,609.6 -3.4329649966,56.4351170685,609.6 -3.4337073317,56.4381078709,609.6 -3.4339572222,56.4411236389,609.6 -3.4559194444,56.4407472222,609.6 -3.4554361111,56.4317694444,609.6 + + + + + + EGRU605E PERTH/SCONE RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7893" txt_name="PERTH/SCONE RWY 27"><tr><td>562637N 0031711W -<br/>562604N 0031709W -<br/>562603N 0031855W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562635N 0031850W -<br/>562637N 0031711W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2863305556,56.4435527778,609.6 -3.3139595278,56.4431115278,609.6 -3.3138835923,56.4400935224,609.6 -3.3143017912,56.4370841262,609.6 -3.3152105556,56.4341081111,609.6 -3.2858444444,56.4345777778,609.6 -3.2863305556,56.4435527778,609.6 + + + + + + EGRU605F PERTH/SCONE RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7919" txt_name="PERTH/SCONE RWY 15"><tr><td>562844N 0032509W -<br/>562900N 0032418W -<br/>562821N 0032337W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562806N 0032429W -<br/>562844N 0032509W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.419075,56.47875,609.6 -3.4081112778,56.4684703889,609.6 -3.4035104538,56.4700697543,609.6 -3.3986671264,56.4714324112,609.6 -3.3936209444,56.4725471944,609.6 -3.4050944444,56.4833083333,609.6 -3.419075,56.47875,609.6 + + + + + + EGRU605G PERTH/SCONE RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7667" txt_name="PERTH/SCONE RWY 33"><tr><td>562404N 0031904W -<br/>562348N 0031954W -<br/>562441N 0032050W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to<br/>562459N 0032002W -<br/>562404N 0031904W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3176638889,56.401125,609.6 -3.3338338333,56.4163559722,609.6 -3.3380343685,56.4144523496,609.6 -3.3425274864,56.4127666313,609.6 -3.3472765278,56.4113125833,609.6 -3.3316138889,56.3965638889,609.6 -3.3176638889,56.401125,609.6 + + + + + + EGRU606A DUNDEE + <table border="1" cellpadding="1" cellspacing="0" row_id="8002" txt_name="DUNDEE"><tr><td>A circle, 2 NM radius, centred at 562709N 0030133W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0258333333,56.4857643835,609.6 -3.0320151227,56.4855879248,609.6 -3.0381312131,56.4850604241,609.6 -3.044116609,56.4841874874,609.6 -3.0499077146,56.4829783912,609.6 -3.0554430142,56.4814459834,609.6 -3.0606637293,56.4796065457,609.6 -3.0655144468,56.4774796192,609.6 -3.0699437087,56.4750877959,609.6 -3.0739045596,56.4724564767,609.6 -3.0773550446,56.4696136006,609.6 -3.0802586524,56.4665893465,609.6 -3.0825847002,56.4634158112,609.6 -3.084308654,56.4601266677,609.6 -3.0854123841,56.4567568071,609.6 -3.085884351,56.4533419671,609.6 -3.0857197208,56.4499183532,609.6 -3.0849204094,56.4465222539,609.6 -3.0834950548,56.4431896566,609.6 -3.0814589189,56.4399558667,609.6 -3.078833719,56.4368551338,609.6 -3.0756473919,56.4339202903,609.6 -3.0719337934,56.4311824048,609.6 -3.067732336,56.4286704544,609.6 -3.0630875691,56.4264110194,609.6 -3.0580487061,56.424428004,609.6 -3.052669104,56.4227423841,609.6 -3.0470056997,56.4213719876,609.6 -3.0411184109,56.4203313065,609.6 -3.035069505,56.4196313452,609.6 -3.0289229457,56.4192795045,609.6 -3.022743721,56.4192795045,609.6 -3.0165971617,56.4196313452,609.6 -3.0105482558,56.4203313065,609.6 -3.0046609669,56.4213719876,609.6 -2.9989975627,56.4227423841,609.6 -2.9936179605,56.424428004,609.6 -2.9885790975,56.4264110194,609.6 -2.9839343306,56.4286704544,609.6 -2.9797328733,56.4311824048,609.6 -2.9760192748,56.4339202903,609.6 -2.9728329477,56.4368551338,609.6 -2.9702077478,56.4399558667,609.6 -2.9681716119,56.4431896566,609.6 -2.9667462573,56.4465222539,609.6 -2.9659469459,56.4499183532,609.6 -2.9657823156,56.4533419671,609.6 -2.9662542826,56.4567568071,609.6 -2.9673580127,56.4601266677,609.6 -2.9690819665,56.4634158112,609.6 -2.9714080142,56.4665893465,609.6 -2.9743116221,56.4696136006,609.6 -2.9777621071,56.4724564767,609.6 -2.981722958,56.4750877959,609.6 -2.9861522199,56.4774796192,609.6 -2.9910029373,56.4796065457,609.6 -2.9962236525,56.4814459834,609.6 -3.001758952,56.4829783912,609.6 -3.0075500577,56.4841874874,609.6 -3.0135354536,56.4850604241,609.6 -3.0196515439,56.4855879248,609.6 -3.0258333333,56.4857643835,609.6 + + + + + + EGRU606B DUNDEE RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7886" txt_name="DUNDEE RWY 09"><tr><td>562654N 0030706W -<br/>562726N 0030705W -<br/>562726N 0030507W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to<br/>562654N 0030507W -<br/>562654N 0030706W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1183416667,56.44835,609.6 -3.0853967222,56.4482048333,609.6 -3.0858557268,56.4511958568,609.6 -3.0858259999,56.4541976161,609.6 -3.0853076667,56.4571856667,609.6 -3.1181916667,56.4573305556,609.6 -3.1183416667,56.44835,609.6 + + + + + + EGRU606C DUNDEE RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7631" txt_name="DUNDEE RWY 27"><tr><td>562723N 0025600W -<br/>562651N 0025600W -<br/>562651N 0025759W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to<br/>562724N 0025758W -<br/>562723N 0025600W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9333166667,56.4564027778,609.6 -2.9662158889,56.4565880278,609.6 -2.9657954518,56.4535952763,609.6 -2.9658639633,56.4505937216,609.6 -2.96642075,56.4476078056,609.6 -2.9334611111,56.4474222222,609.6 -2.9333166667,56.4564027778,609.6 + + + + + + EGRU607A LEUCHARS + <table border="1" cellpadding="1" cellspacing="0" row_id="7655" txt_name="LEUCHARS"><tr><td>A circle, 2.5 NM radius, centred at 562230N 0025132W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8587805556,56.4164726416,609.6 -2.8657021278,56.4162950721,609.6 -2.8725644557,56.4157638834,609.6 -2.8793088068,56.4148836221,609.6 -2.8858774683,56.4136618219,609.6 -2.8922142449,56.4121089388,609.6 -2.8982649438,56.4102382607,609.6 -2.9039778414,56.4080657928,609.6 -2.9093041281,56.4056101194,609.6 -2.9141983267,56.4028922436,609.6 -2.9186186821,56.3999354065,609.6 -2.9225275174,56.3967648868,609.6 -2.9258915536,56.3934077838,609.6 -2.9286821919,56.3898927841,609.6 -2.9308757535,56.3862499157,609.6 -2.9324536776,56.38251029,609.6 -2.9334026742,56.3787058356,609.6 -2.9337148321,56.3748690254,609.6 -2.9333876794,56.3710325982,609.6 -2.9324241985,56.3672292802,609.6 -2.9308327941,56.3634915053,609.6 -2.9286272151,56.3598511391,609.6 -2.9258264316,56.356339208,609.6 -2.9224544677,56.3529856353,609.6 -2.9185401925,56.3498189875,609.6 -2.9141170699,56.3468662319,609.6 -2.9092228713,56.3441525083,609.6 -2.9038993517,56.3417009165,609.6 -2.8981918941,56.3395323205,609.6 -2.8921491227,56.3376651727,609.6 -2.8858224914,56.3361153582,609.6 -2.8792658473,56.3348960602,609.6 -2.8725349765,56.3340176497,609.6 -2.8656871329,56.3334875974,609.6 -2.8587805556,56.333310411,609.6 -2.8518739782,56.3334875974,609.6 -2.8450261346,56.3340176497,609.6 -2.8382952638,56.3348960602,609.6 -2.8317386198,56.3361153582,609.6 -2.8254119884,56.3376651727,609.6 -2.8193692171,56.3395323205,609.6 -2.8136617594,56.3417009165,609.6 -2.8083382398,56.3441525083,609.6 -2.8034440412,56.3468662319,609.6 -2.7990209186,56.3498189875,609.6 -2.7951066434,56.3529856353,609.6 -2.7917346795,56.356339208,609.6 -2.788933896,56.3598511391,609.6 -2.786728317,56.3634915053,609.6 -2.7851369126,56.3672292802,609.6 -2.7841734317,56.3710325982,609.6 -2.783846279,56.3748690254,609.6 -2.7841584369,56.3787058356,609.6 -2.7851074336,56.38251029,609.6 -2.7866853576,56.3862499157,609.6 -2.7888789192,56.3898927841,609.6 -2.7916695575,56.3934077838,609.6 -2.7950335937,56.3967648868,609.6 -2.798942429,56.3999354065,609.6 -2.8033627844,56.4028922436,609.6 -2.808256983,56.4056101194,609.6 -2.8135832697,56.4080657928,609.6 -2.8192961673,56.4102382607,609.6 -2.8253468662,56.4121089388,609.6 -2.8316836428,56.4136618219,609.6 -2.8382523043,56.4148836221,609.6 -2.8449966554,56.4157638834,609.6 -2.8518589833,56.4162950721,609.6 -2.8587805556,56.4164726416,609.6 + + + + + + EGRU607B LEUCHARS RWY 04 + <table border="1" cellpadding="1" cellspacing="0" row_id="7504" txt_name="LEUCHARS RWY 04"><tr><td>561957N 0025452W -<br/>562017N 0025539W -<br/>562050N 0025453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to<br/>562028N 0025410W -<br/>561957N 0025452W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9144206944,56.3325690833,609.6 -2.9027777778,56.3412401944,609.6 -2.9070505126,56.3430960833,609.6 -2.9110705021,56.3451187835,609.6 -2.9148166667,56.3472976944,609.6 -2.9273748889,56.33794275,609.6 -2.9144206944,56.3325690833,609.6 + + + + + + EGRU607C LEUCHARS RWY 22 + <table border="1" cellpadding="1" cellspacing="0" row_id="7540" txt_name="LEUCHARS RWY 22"><tr><td>562509N 0024905W -<br/>562449N 0024819W -<br/>562428N 0024847W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to<br/>562445N 0024937W -<br/>562509N 0024905W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8181688333,56.4190974444,609.6 -2.8269991944,56.4125516667,609.6 -2.8221647812,56.4111759222,609.6 -2.8175231097,56.4096095711,609.6 -2.8130985833,56.4078608611,609.6 -2.8051870833,56.4137238333,609.6 -2.8181688333,56.4190974444,609.6 + + + + + + EGRU607D LEUCHARS RWY 08 + <table border="1" cellpadding="1" cellspacing="0" row_id="7597" txt_name="LEUCHARS RWY 08"><tr><td>562145N 0025723W -<br/>562217N 0025731W -<br/>562224N 0025601W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to<br/>562152N 0025553W -<br/>562145N 0025723W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9562513333,56.3625036111,609.6 -2.9313368611,56.36452075,609.6 -2.9324977062,56.3674495154,609.6 -2.9332753622,56.370417093,609.6 -2.9336656944,56.3734080556,609.6 -2.9585670556,56.3713919722,609.6 -2.9562513333,56.3625036111,609.6 + + + + + + EGRU607E LEUCHARS RWY 26 + <table border="1" cellpadding="1" cellspacing="0" row_id="8060" txt_name="LEUCHARS RWY 26"><tr><td>562314N 0024541W -<br/>562242N 0024532W -<br/>562235N 0024702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to<br/>562307N 0024710W -<br/>562314N 0024541W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7612772778,56.3872223611,609.6 -2.7861945833,56.3852410278,609.6 -2.7850416753,56.3823112446,609.6 -2.7842725202,56.3793429756,609.6 -2.7838910278,56.3763516667,609.6 -2.7589605833,56.3783340278,609.6 -2.7612772778,56.3872223611,609.6 + + + + + + EGRU701A BARRA + <table border="1" cellpadding="1" cellspacing="0" row_id="7818" txt_name="BARRA"><tr><td>A circle, 2 NM radius, centred at 570122N 0072635W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.4430555556,57.0560390985,609.6 -7.4493317926,57.0558626526,609.6 -7.455541323,57.0553351905,609.6 -7.4616181547,57.054462318,609.6 -7.4674977172,57.0532533114,609.6 -7.473117552,57.0517210185,609.6 -7.478417981,57.0498817204,609.6 -7.4833427432,57.0477549579,609.6 -7.4878395942,57.045363322,609.6 -7.491860862,57.0427322129,609.6 -7.4953639526,57.0398895683,609.6 -7.4983117994,57.0368655654,609.6 -7.5006732542,57.0336922995,609.6 -7.5024234124,57.0304034414,609.6 -7.5035438719,57.0270338796,609.6 -7.5040229219,57.0236193492,609.6 -7.5038556597,57.0201960523,609.6 -7.5030440356,57.0168002742,609.6 -7.5015968243,57.0134679986,609.6 -7.499529525,57.0102345269,609.6 -7.4968641904,57.0071341048,609.6 -7.4936291869,57.0041995606,609.6 -7.4898588892,57.0014619587,609.6 -7.4855933127,56.9989502723,609.6 -7.4808776867,56.996691078,609.6 -7.4757619752,56.9947082762,609.6 -7.4703003474,56.9930228397,609.6 -7.4645506066,56.9916525934,609.6 -7.4585735812,56.9906120271,609.6 -7.4524324849,56.9899121433,609.6 -7.4461922524,56.9895603417,609.6 -7.4399188587,56.9895603417,609.6 -7.4336786262,56.9899121433,609.6 -7.4275375299,56.9906120271,609.6 -7.4215605045,56.9916525934,609.6 -7.4158107637,56.9930228397,609.6 -7.410349136,56.9947082762,609.6 -7.4052334244,56.996691078,609.6 -7.4005177984,56.9989502723,609.6 -7.3962522219,57.0014619587,609.6 -7.3924819242,57.0041995606,609.6 -7.3892469207,57.0071341048,609.6 -7.3865815861,57.0102345269,609.6 -7.3845142869,57.0134679986,609.6 -7.3830670755,57.0168002742,609.6 -7.3822554514,57.0201960523,609.6 -7.3820881892,57.0236193492,609.6 -7.3825672392,57.0270338796,609.6 -7.3836876987,57.0304034414,609.6 -7.3854378569,57.0336922995,609.6 -7.3877993117,57.0368655654,609.6 -7.3907471585,57.0398895683,609.6 -7.3942502491,57.0427322129,609.6 -7.3982715169,57.045363322,609.6 -7.4027683679,57.0477549579,609.6 -7.4076931301,57.0498817204,609.6 -7.4129935591,57.0517210185,609.6 -7.4186133939,57.0532533114,609.6 -7.4244929564,57.054462318,609.6 -7.4305697881,57.0553351905,609.6 -7.4367793185,57.0558626526,609.6 -7.4430555556,57.0560390985,609.6 + + + + + + EGRU701B BARRA RWY 07 + <table border="1" cellpadding="1" cellspacing="0" row_id="8087" txt_name="BARRA RWY 07"><tr><td>570009N 0073107W -<br/>570038N 0073131W -<br/>570058N 0073010W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570027N 0072950W -<br/>570009N 0073107W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5186611111,57.0023805556,609.6 -7.4972838889,57.0075711389,609.6 -7.4995843138,57.0103081042,609.6 -7.5014219593,57.0131473248,609.6 -7.5027816667,57.0160655556,609.6 -7.5253361111,57.0105888889,609.6 -7.5186611111,57.0023805556,609.6 + + + + + + EGRU701C BARRA RWY 25 + <table border="1" cellpadding="1" cellspacing="0" row_id="7656" txt_name="BARRA RWY 25"><tr><td>570300N 0072146W -<br/>570230N 0072122W -<br/>570204N 0072310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570233N 0072338W -<br/>570300N 0072146W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3628166667,57.049925,609.6 -7.39384875,57.0424367222,609.6 -7.3907906377,57.039929051,609.6 -7.3881615015,57.0372808229,609.6 -7.3859828056,57.0345137778,609.6 -7.3561305556,57.0417166667,609.6 -7.3628166667,57.049925,609.6 + + + + + + EGRU701D BARRA RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7678" txt_name="BARRA RWY 11"><tr><td>570143N 0073151W -<br/>570214N 0073140W -<br/>570204N 0073000W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570133N 0073014W -<br/>570143N 0073151W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5307805556,57.0285111111,609.6 -7.5037998333,57.02575225,609.6 -7.5030623655,57.0287291903,609.6 -7.5018352022,57.0316576943,609.6 -7.50012825,57.0345138611,609.6 -7.5277277778,57.0373361111,609.6 -7.5307805556,57.0285111111,609.6 + + + + + + EGRU701E BARRA RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="8028" txt_name="BARRA RWY 29"><tr><td>570111N 0072125W -<br/>570039N 0072136W -<br/>570049N 0072304W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570121N 0072255W -<br/>570111N 0072125W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3568277778,57.0197555556,609.6 -7.3820743056,57.0223684167,609.6 -7.3823931586,57.0193695108,609.6 -7.3832066545,57.0163985197,609.6 -7.3845080556,57.0134796667,609.6 -7.3598777778,57.0109305556,609.6 -7.3568277778,57.0197555556,609.6 + + + + + + EGRU701F BARRA RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="7513" txt_name="BARRA RWY 15"><tr><td>570324N 0073025W -<br/>570345N 0072940W -<br/>570303N 0072834W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570242N 0072919W -<br/>570324N 0073025W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.5068583333,57.0565277778,609.6 -7.4886011111,57.0449058333,609.6 -7.4847575404,57.047054711,609.6 -7.4805738096,57.0490058771,609.6 -7.476084,57.0507434167,609.6 -7.4943305556,57.0623611111,609.6 -7.5068583333,57.0565277778,609.6 + + + + + + EGRU701G BARRA RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7853" txt_name="BARRA RWY 33"><tr><td>565921N 0072247W -<br/>565900N 0072332W -<br/>565941N 0072436W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to<br/>570002N 0072351W -<br/>565921N 0072247W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3795888889,56.9891388889,609.6 -7.3975619444,57.0006344167,609.6 -7.4014054781,56.9984881114,609.6 -7.4055874261,56.9965394753,609.6 -7.41007375,56.9948043333,609.6 -7.3920916667,56.9833055556,609.6 -7.3795888889,56.9891388889,609.6 + + + + + + EGRU702A BENBECULA + <table border="1" cellpadding="1" cellspacing="0" row_id="8059" txt_name="BENBECULA"><tr><td>A circle, 2 NM radius, centred at 572850N 0072150W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3638888889,57.5138144373,609.6 -7.370243523,57.5136380016,609.6 -7.376530614,57.5131105699,609.6 -7.3826833427,57.512237748,609.6 -7.3886363291,57.5110288122,609.6 -7.3943263326,57.50949661,609.6 -7.3996929278,57.5076574223,609.6 -7.4046791501,57.5055307894,609.6 -7.4092321026,57.5031393019,609.6 -7.4133035183,57.5005083591,609.6 -7.4168502725,57.4976658978,609.6 -7.4198348381,57.4946420944,609.6 -7.4222256804,57.4914690423,609.6 -7.4239975874,57.488180411,609.6 -7.4251319309,57.4848110868,609.6 -7.425616858,57.4813968027,609.6 -7.425447409,57.4779737584,609.6 -7.4246255628,57.4745782363,609.6 -7.4231602077,57.4712462172,609.6 -7.42106704,57.4680129995,609.6 -7.4183683908,57.4649128256,609.6 -7.4150929832,57.4619785206,609.6 -7.4112756225,57.4592411455,609.6 -7.4069568246,57.4567296703,609.6 -7.4021823834,57.4544706685,609.6 -7.3970028855,57.4524880377,609.6 -7.3914731746,57.450802748,609.6 -7.3856517729,57.4494326221,609.6 -7.3796002648,57.4483921478,609.6 -7.3733826489,57.4476923261,609.6 -7.3670646665,57.4473405559,609.6 -7.3607131113,57.4473405559,609.6 -7.3543951289,57.4476923261,609.6 -7.348177513,57.4483921478,609.6 -7.3421260049,57.4494326221,609.6 -7.3363046032,57.450802748,609.6 -7.3307748923,57.4524880377,609.6 -7.3255953944,57.4544706685,609.6 -7.3208209532,57.4567296703,609.6 -7.3165021552,57.4592411455,609.6 -7.3126847946,57.4619785206,609.6 -7.3094093869,57.4649128256,609.6 -7.3067107378,57.4680129995,609.6 -7.3046175701,57.4712462172,609.6 -7.303152215,57.4745782363,609.6 -7.3023303687,57.4779737584,609.6 -7.3021609198,57.4813968027,609.6 -7.3026458469,57.4848110868,609.6 -7.3037801904,57.488180411,609.6 -7.3055520973,57.4914690423,609.6 -7.3079429397,57.4946420944,609.6 -7.3109275052,57.4976658978,609.6 -7.3144742595,57.5005083591,609.6 -7.3185456752,57.5031393019,609.6 -7.3230986276,57.5055307894,609.6 -7.32808485,57.5076574223,609.6 -7.3334514452,57.50949661,609.6 -7.3391414487,57.5110288122,609.6 -7.3450944351,57.512237748,609.6 -7.3512471638,57.5131105699,609.6 -7.3575342548,57.5136380016,609.6 -7.3638888889,57.5138144373,609.6 + + + + + + EGRU702B BENBECULA RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="8063" txt_name="BENBECULA RWY 06"><tr><td>572652N 0072615W -<br/>572719N 0072649W -<br/>572756N 0072509W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to<br/>572730N 0072435W -<br/>572652N 0072615W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.4375166667,57.4478472222,609.6 -7.4096192222,57.4582158611,609.6 -7.4131712731,57.460527276,609.6 -7.4163226737,57.46300177,609.6 -7.4190477222,57.4656192222,609.6 -7.4469583333,57.4552444444,609.6 -7.4375166667,57.4478472222,609.6 + + + + + + EGRU702C BENBECULA RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7514" txt_name="BENBECULA RWY 24"><tr><td>573054N 0071710W -<br/>573027N 0071636W -<br/>572944N 0071832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to<br/>573011N 0071906W -<br/>573054N 0071710W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.2860777778,57.5148805556,609.6 -7.31827175,57.5029787222,609.6 -7.3147038122,57.5006722278,609.6 -7.3115371197,57.4982018809,609.6 -7.3087974167,57.4955878333,609.6 -7.2766166667,57.5074833333,609.6 -7.2860777778,57.5148805556,609.6 + + + + + + EGRU702D BENBECULA RWY 17 + <table border="1" cellpadding="1" cellspacing="0" row_id="7718" txt_name="BENBECULA RWY 17"><tr><td>573147N 0072334W -<br/>573154N 0072235W -<br/>573049N 0072207W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to<br/>573043N 0072306W -<br/>573147N 0072334W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3926600556,57.5296843333,609.6 -7.3849875,57.5118143889,609.6 -7.379665191,57.5127115306,609.6 -7.3742140602,57.5133465673,609.6 -7.3686786111,57.5137143056,609.6 -7.3763938333,57.53170225,609.6 -7.3926600556,57.5296843333,609.6 + + + + + + EGRU702E BENBECULA RWY 35 + <table border="1" cellpadding="1" cellspacing="0" row_id="7666" txt_name="BENBECULA RWY 35"><tr><td>572601N 0072004W -<br/>572554N 0072102W -<br/>572651N 0072127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to<br/>572659N 0072028W -<br/>572601N 0072004W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-7.3344309722,57.4336456389,609.6 -7.3412491111,57.4496147778,609.6 -7.3465157972,57.4486412763,609.6 -7.3519236088,57.4479274827,609.6 -7.3574286111,57.4474791944,609.6 -7.3506536944,57.4316276944,609.6 -7.3344309722,57.4336456389,609.6 + + + + + + EGRU703A INVERNESS + <table border="1" cellpadding="1" cellspacing="0" row_id="7879" txt_name="INVERNESS"><tr><td>A circle, 2.5 NM radius, centred at 573233N 0040251W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.0475444444,57.5840676082,609.6 -4.0546862389,57.5838900633,609.6 -4.0617668949,57.5833589483,609.6 -4.0687258029,57.5824788098,609.6 -4.0755034058,57.5812571816,609.6 -4.0820417136,57.5797045197,609.6 -4.088284804,57.577834112,609.6 -4.0941793039,57.5756619633,609.6 -4.0996748488,57.5732066576,609.6 -4.104724515,57.5704891971,609.6 -4.1092852208,57.5675328218,609.6 -4.1133180947,57.564362809,609.6 -4.1167888052,57.5610062559,609.6 -4.1196678512,57.5574918464,609.6 -4.1219308101,57.5538496052,609.6 -4.123558541,57.5501106398,609.6 -4.1245373428,57.5463068745,609.6 -4.1248590642,57.5424707767,609.6 -4.1245211671,57.5386350794,609.6 -4.1235267406,57.5348325024,609.6 -4.1218844678,57.5310954725,609.6 -4.1196085452,57.527455848,609.6 -4.1167185551,57.5239446474,609.6 -4.1132392927,57.520591786,609.6 -4.1092005504,57.5174258222,609.6 -4.1046368596,57.5144737151,609.6 -4.0995871934,57.5117605968,609.6 -4.0940946335,57.5093095592,609.6 -4.0882060019,57.5071414595,609.6 -4.0819714634,57.5052747435,609.6 -4.0754440997,57.5037252905,609.6 -4.0686794606,57.5025062791,609.6 -4.0617350944,57.501628076,609.6 -4.0546700632,57.5010981493,609.6 -4.0475444444,57.500921005,609.6 -4.0404188257,57.5010981493,609.6 -4.0333537944,57.501628076,609.6 -4.0264094283,57.5025062791,609.6 -4.0196447892,57.5037252905,609.6 -4.0131174255,57.5052747435,609.6 -4.006882887,57.5071414595,609.6 -4.0009942554,57.5093095592,609.6 -3.9955016955,57.5117605968,609.6 -3.9904520293,57.5144737151,609.6 -3.9858883385,57.5174258222,609.6 -3.9818495962,57.520591786,609.6 -3.9783703338,57.5239446474,609.6 -3.9754803436,57.527455848,609.6 -3.9732044211,57.5310954725,609.6 -3.9715621483,57.5348325024,609.6 -3.9705677217,57.5386350794,609.6 -3.9702298247,57.5424707767,609.6 -3.9705515461,57.5463068745,609.6 -3.9715303479,57.5501106398,609.6 -3.9731580788,57.5538496052,609.6 -3.9754210377,57.5574918464,609.6 -3.9783000837,57.5610062559,609.6 -3.9817707942,57.564362809,609.6 -3.9858036681,57.5675328218,609.6 -3.9903643739,57.5704891971,609.6 -3.99541404,57.5732066576,609.6 -4.000909585,57.5756619633,609.6 -4.0068040849,57.577834112,609.6 -4.0130471752,57.5797045197,609.6 -4.0195854831,57.5812571816,609.6 -4.026363086,57.5824788098,609.6 -4.033321994,57.5833589483,609.6 -4.04040265,57.5838900633,609.6 -4.0475444444,57.5840676082,609.6 + + + + + + EGRU703B INVERNESS RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8055" txt_name="INVERNESS RWY 05"><tr><td>573017N 0040700W -<br/>573042N 0040739W -<br/>573108N 0040641W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to<br/>573044N 0040602W -<br/>573017N 0040700W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1166388889,57.5047583333,609.6 -4.1004858611,57.5122078611,609.6 -4.1044062774,57.5143384338,609.6 -4.1080315965,57.5166154193,609.6 -4.1113429444,57.519027,609.6 -4.1274805556,57.5115833333,609.6 -4.1166388889,57.5047583333,609.6 + + + + + + EGRU703C INVERNESS RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="8144" txt_name="INVERNESS RWY 23"><tr><td>573450N 0035839W -<br/>573426N 0035800W -<br/>573357N 0035901W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to<br/>573422N 0035940W -<br/>573450N 0035839W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9774833333,57.580575,609.6 -3.9945199444,57.5727610833,609.6 -3.990598808,57.5706269755,609.6 -3.9869746432,57.5683464492,609.6 -3.9836663056,57.5659313889,609.6 -3.9666166667,57.57375,609.6 -3.9774833333,57.580575,609.6 + + + + + + EGRU703D INVERNESS RWY 11 + <table border="1" cellpadding="1" cellspacing="0" row_id="7692" txt_name="INVERNESS RWY 11"><tr><td>573320N 0040829W -<br/>573350N 0040809W -<br/>573337N 0040702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to<br/>573307N 0040722W -<br/>573320N 0040829W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-4.1413694444,57.5554416667,609.6 -4.1228588611,57.5519122778,609.6 -4.1214032257,57.5548065424,609.6 -4.119563074,57.5576368626,609.6 -4.1173478889,57.5603885,609.6 -4.1357638889,57.5639,609.6 -4.1413694444,57.5554416667,609.6 + + + + + + EGRU703E INVERNESS RWY 29 + <table border="1" cellpadding="1" cellspacing="0" row_id="8056" txt_name="INVERNESS RWY 29"><tr><td>573154N 0035803W -<br/>573124N 0035823W -<br/>573127N 0035841W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to<br/>573158N 0035821W -<br/>573154N 0035803W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.9673888889,57.5316694444,609.6 -3.9724428889,57.532641,609.6 -3.9739612196,57.5297563839,609.6 -3.9758618079,57.5269380967,609.6 -3.9781346944,57.5242007778,609.6 -3.9729861111,57.5232111111,609.6 -3.9673888889,57.5316694444,609.6 + + + + + + EGRU705A LOSSIEMOUTH + <table border="1" cellpadding="1" cellspacing="0" row_id="7966" txt_name="LOSSIEMOUTH"><tr><td>A circle, 2.5 NM radius, centred at 574224N 0032016W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.3378888889,57.7482304105,609.6 -3.3450630202,57.7480528689,609.6 -3.352175735,57.747521764,609.6 -3.3591661478,57.7466416423,609.6 -3.365974431,57.7454200376,609.6 -3.3725423308,57.7438674061,609.6 -3.3788136709,57.7419970354,609.6 -3.3847348362,57.7398249306,609.6 -3.3902552337,57.7373696753,609.6 -3.3953277273,57.734652272,609.6 -3.3999090406,57.7316959604,609.6 -3.4039601267,57.7285260175,609.6 -3.4074464995,57.7251695403,609.6 -3.4103385256,57.7216552125,609.6 -3.4126116729,57.7180130581,609.6 -3.4142467157,57.7142741844,609.6 -3.4152298924,57.7104705148,609.6 -3.4155530167,57.7066345159,609.6 -3.4152135405,57.7027989203,609.6 -3.4142145688,57.6989964465,609.6 -3.4125648257,57.6952595206,609.6 -3.4102785734,57.6916199997,609.6 -3.4073754839,57.6881089011,609.6 -3.4038804661,57.6847561392,609.6 -3.3998234477,57.6815902711,609.6 -3.3952391168,57.6786382549,609.6 -3.3901666232,57.6759252214,609.6 -3.3846492432,57.6734742616,609.6 -3.3787340102,57.6713062315,609.6 -3.3724713151,57.6694395761,609.6 -3.3659144786,57.6678901739,609.6 -3.3591193005,57.6666712026,609.6 -3.352143588,57.6657930287,609.6 -3.3450466683,57.6652631197,609.6 -3.3378888889,57.6650859813,609.6 -3.3307311095,57.6652631197,609.6 -3.3236341898,57.6657930287,609.6 -3.3166584773,57.6666712026,609.6 -3.3098632992,57.6678901739,609.6 -3.3033064627,57.6694395761,609.6 -3.2970437676,57.6713062315,609.6 -3.2911285346,57.6734742616,609.6 -3.2856111546,57.6759252214,609.6 -3.280538661,57.6786382549,609.6 -3.2759543301,57.6815902711,609.6 -3.2718973117,57.6847561392,609.6 -3.2684022939,57.6881089011,609.6 -3.2654992044,57.6916199997,609.6 -3.2632129521,57.6952595206,609.6 -3.261563209,57.6989964465,609.6 -3.2605642373,57.7027989203,609.6 -3.2602247611,57.7066345159,609.6 -3.2605478854,57.7104705148,609.6 -3.2615310621,57.7142741844,609.6 -3.2631661049,57.7180130581,609.6 -3.2654392522,57.7216552125,609.6 -3.2683312783,57.7251695403,609.6 -3.2718176511,57.7285260175,609.6 -3.2758687372,57.7316959604,609.6 -3.2804500505,57.734652272,609.6 -3.285522544,57.7373696753,609.6 -3.2910429416,57.7398249306,609.6 -3.2969641068,57.7419970354,609.6 -3.303235447,57.7438674061,609.6 -3.3098033468,57.7454200376,609.6 -3.3166116299,57.7466416423,609.6 -3.3236020428,57.747521764,609.6 -3.3307147576,57.7480528689,609.6 -3.3378888889,57.7482304105,609.6 + + + + + + EGRU705B LOSSIEMOUTH RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8073" txt_name="LOSSIEMOUTH RWY 05"><tr><td>573945N 0032419W -<br/>574007N 0032502W -<br/>574048N 0032350W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to<br/>574025N 0032307W -<br/>573945N 0032419W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4052303889,57.6623962222,609.6 -3.3851451111,57.6736762778,609.6 -3.3894605228,57.6755851141,609.6 -3.3935083929,57.6776554804,609.6 -3.3972676667,57.6798766389,609.6 -3.4173429722,57.6686000833,609.6 -3.4052303889,57.6623962222,609.6 + + + + + + EGRU705C LOSSIEMOUTH RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7749" txt_name="LOSSIEMOUTH RWY 23"><tr><td>574503N 0031614W -<br/>574441N 0031530W -<br/>574400N 0031642W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to<br/>574423N 0031726W -<br/>574503N 0031614W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2704251389,57.7508905278,609.6 -3.2905774444,57.7396351944,609.6 -3.2862578363,57.7377241466,609.6 -3.2822074459,57.7356514462,609.6 -3.2784473611,57.7334278889,609.6 -3.2582850556,57.74468675,609.6 -3.2704251389,57.7508905278,609.6 + + + + + + EGRU705D LOSSIEMOUTH RWY 10 + <table border="1" cellpadding="1" cellspacing="0" row_id="8139" txt_name="LOSSIEMOUTH RWY 10"><tr><td>574228N 0032535W -<br/>574300N 0032529W -<br/>574258N 0032449W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to<br/>574225N 0032456W -<br/>574228N 0032535W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.4264832778,57.7077121111,609.6 -3.4155498889,57.7070576667,609.6 -3.4152973401,57.7100528307,609.6 -3.4146420388,57.7130304583,609.6 -3.4135873056,57.7159750556,609.6 -3.4245959444,57.716634,609.6 -3.4264832778,57.7077121111,609.6 + + + + + + EGRU705E LOSSIEMOUTH RWY 28 + <table border="1" cellpadding="1" cellspacing="0" row_id="7959" txt_name="LOSSIEMOUTH RWY 28"><tr><td>574217N 0031343W -<br/>574145N 0031350W -<br/>574152N 0031543W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to<br/>574224N 0031537W -<br/>574217N 0031343W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.2287245833,57.7047635833,609.6 -3.2602247222,57.7066935278,609.6 -3.260425149,57.7036972473,609.6 -3.2610283953,57.7007164886,609.6 -3.2620312222,57.69776675,609.6 -3.2306113056,57.6958416944,609.6 -3.2287245833,57.7047635833,609.6 + + + + + + EGRU706A ABERDEEN/DYCE + <table border="1" cellpadding="1" cellspacing="0" row_id="7938" txt_name="ABERDEEN/DYCE"><tr><td>A circle, 2.5 NM radius, centred at 571209N 0021153W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1980555556,57.2440754236,609.6 -2.2051314822,57.2438978716,609.6 -2.2121468371,57.2433667355,609.6 -2.2190415719,57.2424865618,609.6 -2.2257566814,57.2412648843,609.6 -2.2322347123,57.239712159,609.6 -2.2384202596,57.2378416738,609.6 -2.2442604437,57.2356694335,609.6 -2.249705365,57.2332140222,609.6 -2.2547085326,57.2304964423,609.6 -2.2592272616,57.2275399342,609.6 -2.2632230376,57.2243697755,609.6 -2.266661844,57.221013064,609.6 -2.2695144494,57.2174984844,609.6 -2.2717566538,57.2138560622,609.6 -2.2733694897,57.2101169061,609.6 -2.2743393788,57.2063129417,609.6 -2.2746582417,57.2024766378,609.6 -2.2743235599,57.1986407293,609.6 -2.2733383906,57.1948379377,609.6 -2.2717113336,57.1911006919,609.6 -2.2694564514,57.1874608524,609.6 -2.2665931431,57.1839494398,609.6 -2.2631459735,57.180596372,609.6 -2.2591444585,57.1774302095,609.6 -2.2546228104,57.174477914,609.6 -2.2496196428,57.1717646198,609.6 -2.2441776406,57.1693134211,609.6 -2.2383431954,57.1671451771,609.6 -2.2321660113,57.1652783355,609.6 -2.2256986832,57.1637287773,609.6 -2.2189962516,57.1625096825,609.6 -2.2121157379,57.1616314191,609.6 -2.2051156633,57.1611014558,609.6 -2.1980555556,57.1609242992,609.6 -2.1909954478,57.1611014558,609.6 -2.1839953732,57.1616314191,609.6 -2.1771148595,57.1625096825,609.6 -2.1704124279,57.1637287773,609.6 -2.1639450998,57.1652783355,609.6 -2.1577679157,57.1671451771,609.6 -2.1519334705,57.1693134211,609.6 -2.1464914683,57.1717646198,609.6 -2.1414883007,57.174477914,609.6 -2.1369666526,57.1774302095,609.6 -2.1329651376,57.180596372,609.6 -2.129517968,57.1839494398,609.6 -2.1266546597,57.1874608524,609.6 -2.1243997775,57.1911006919,609.6 -2.1227727205,57.1948379377,609.6 -2.1217875512,57.1986407293,609.6 -2.1214528694,57.2024766378,609.6 -2.1217717323,57.2063129417,609.6 -2.1227416214,57.2101169061,609.6 -2.1243544573,57.2138560622,609.6 -2.1265966617,57.2174984844,609.6 -2.1294492671,57.221013064,609.6 -2.1328880735,57.2243697755,609.6 -2.1368838495,57.2275399342,609.6 -2.1414025785,57.2304964423,609.6 -2.1464057461,57.2332140222,609.6 -2.1518506674,57.2356694335,609.6 -2.1576908515,57.2378416738,609.6 -2.1638763988,57.239712159,609.6 -2.1703544298,57.2412648843,609.6 -2.1770695392,57.2424865618,609.6 -2.183964274,57.2433667355,609.6 -2.1909796289,57.2438978716,609.6 -2.1980555556,57.2440754236,609.6 + + + + + + EGRU706B ABERDEEN/DYCE RWY 05 + <table border="1" cellpadding="1" cellspacing="0" row_id="8084" txt_name="ABERDEEN/DYCE RWY 05"><tr><td>571012N 0021521W -<br/>571035N 0021602W -<br/>571046N 0021542W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>571021N 0021503W -<br/>571012N 0021521W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2558333333,57.1699,609.6 -2.2509389444,57.1724325,609.6 -2.2547998124,57.1745835737,609.6 -2.2583651059,57.1768803442,609.6 -2.2616161667,57.1793108611,609.6 -2.267225,57.1764083333,609.6 -2.2558333333,57.1699,609.6 + + + + + + EGRU706C ABERDEEN/DYCE RWY 23 + <table border="1" cellpadding="1" cellspacing="0" row_id="7963" txt_name="ABERDEEN/DYCE RWY 23"><tr><td>571428N 0020830W -<br/>571405N 0020749W -<br/>571347N 0020824W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>571409N 0020908W -<br/>571428N 0020830W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1416416667,57.2412277778,609.6 -2.1521781389,57.2358029722,609.6 -2.1478649411,57.2339182045,609.6 -2.143814412,57.2318693419,609.6 -2.1400476944,57.2296671111,609.6 -2.1302277778,57.2347222222,609.6 -2.1416416667,57.2412277778,609.6 + + + + + + EGRU706D ABERDEEN/DYCE RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="7911" txt_name="ABERDEEN/DYCE RWY 14"><tr><td>571403N 0021541W -<br/>571424N 0021456W -<br/>571410N 0021434W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>571349N 0021518W -<br/>571403N 0021541W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.26135,57.2341222222,609.6 -2.2551375556,57.2302386389,609.6 -2.2513035743,57.2323996757,609.6 -2.2471918743,57.2344050786,609.6 -2.2428238611,57.2362443889,609.6 -2.2488305556,57.24,609.6 -2.26135,57.2341222222,609.6 + + + + + + EGRU706E ABERDEEN/DYCE RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="8049" txt_name="ABERDEEN/DYCE RWY 32"><tr><td>571005N 0020803W -<br/>570944N 0020848W -<br/>571004N 0020920W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>571025N 0020835W -<br/>571005N 0020803W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.13425,57.1681777778,609.6 -2.1429397222,57.1736382222,609.6 -2.1469152275,57.1715566524,609.6 -2.1511562433,57.1696360549,609.6 -2.1556406944,57.1678863889,609.6 -2.1467444444,57.1622972222,609.6 -2.13425,57.1681777778,609.6 + + + + + + EGRU706F ABERDEEN/DYCE RWY 16 + <table border="1" cellpadding="1" cellspacing="0" row_id="7598" txt_name="ABERDEEN/DYCE RWY 16"><tr><td>571502N 0021434W -<br/>571514N 0021338W -<br/>571433N 0021308W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>571421N 0021403W -<br/>571502N 0021434W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.2426722222,57.2505722222,609.6 -2.2342207778,57.2391555278,609.6 -2.2292543468,57.2404748588,609.6 -2.2241251251,57.2415964682,609.6 -2.2188598611,57.2425145,609.6 -2.2272916667,57.2539111111,609.6 -2.2426722222,57.2505722222,609.6 + + + + + + EGRU706G ABERDEEN/DYCE RWY 34 + <table border="1" cellpadding="1" cellspacing="0" row_id="7913" txt_name="ABERDEEN/DYCE RWY 34"><tr><td>570915N 0020914W -<br/>570903N 0021009W -<br/>570945N 0021039W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>570957N 0020944W -<br/>570915N 0020914W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1537638889,57.1542722222,609.6 -2.1622190556,57.1657595833,609.6 -2.1671869666,57.1644531612,609.6 -2.1723149548,57.1633444667,609.6 -2.1775764167,57.16243925,609.6 -2.1691027778,57.1509333333,609.6 -2.1537638889,57.1542722222,609.6 + + + + + + EGRU706I ABERDEEN/DYCE RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7543" txt_name="ABERDEEN/DYCE RWY 36"><tr><td>570935N 0021131W -<br/>570935N 0021231W -<br/>570941N 0021231W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to<br/>570940N 0021131W -<br/>570935N 0021131W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.1920326944,57.1597811944,609.6 -2.1920731667,57.1610514167,609.6 -2.1975928553,57.1609250685,609.6 -2.2031149457,57.1610151918,609.6 -2.20861075,57.1613213333,609.6 -2.2085559444,57.1596245,609.6 -2.1920326944,57.1597811944,609.6 + + + + + + EGRU801A STORNOWAY + <table border="1" cellpadding="1" cellspacing="0" row_id="8138" txt_name="STORNOWAY"><tr><td>A circle, 2.5 NM radius, centred at 581256N 0061952W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3310666667,58.2571659496,609.6 -6.3383433246,58.2569884183,609.6 -6.3455576842,58.2564573442,609.6 -6.3526479856,58.2555772738,609.6 -6.3595535425,58.2543557411,609.6 -6.3662152656,58.2528032022,609.6 -6.3725761731,58.2509329449,609.6 -6.3785818819,58.2487609742,609.6 -6.3841810752,58.2463058737,609.6 -6.3893259432,58.2435886454,609.6 -6.3939725923,58.2406325289,609.6 -6.3980814193,58.2374628007,609.6 -6.4016174482,58.2341065568,609.6 -6.4045506258,58.2305924798,609.6 -6.4068560739,58.2269505926,609.6 -6.4085142969,58.2232120008,609.6 -6.4095113418,58.2194086259,609.6 -6.4098389112,58.2155729323,609.6 -6.4094944263,58.21173765,609.6 -6.4084810417,58.2079354948,609.6 -6.4068076117,58.2041988897,609.6 -6.4044886068,58.2005596887,609.6 -6.4015439844,58.1970489057,609.6 -6.3979990124,58.1936964513,609.6 -6.3938840486,58.1905308793,609.6 -6.3892342779,58.1875791442,609.6 -6.3840894099,58.1848663732,609.6 -6.3784933381,58.182415654,609.6 -6.3724937661,58.1802478395,609.6 -6.3661418016,58.1783813719,609.6 -6.3594915233,58.1768321269,609.6 -6.3525995233,58.1756132803,609.6 -6.3455244289,58.1747351967,609.6 -6.338326409,58.1742053424,609.6 -6.3310666667,58.1740282223,609.6 -6.3238069243,58.1742053424,609.6 -6.3166089044,58.1747351967,609.6 -6.3095338101,58.1756132803,609.6 -6.30264181,58.1768321269,609.6 -6.2959915317,58.1783813719,609.6 -6.2896395673,58.1802478395,609.6 -6.2836399953,58.182415654,609.6 -6.2780439235,58.1848663732,609.6 -6.2728990554,58.1875791442,609.6 -6.2682492848,58.1905308793,609.6 -6.2641343209,58.1936964513,609.6 -6.2605893489,58.1970489057,609.6 -6.2576447265,58.2005596887,609.6 -6.2553257217,58.2041988897,609.6 -6.2536522916,58.2079354948,609.6 -6.2526389071,58.21173765,609.6 -6.2522944221,58.2155729323,609.6 -6.2526219915,58.2194086259,609.6 -6.2536190365,58.2232120008,609.6 -6.2552772594,58.2269505926,609.6 -6.2575827075,58.2305924798,609.6 -6.2605158851,58.2341065568,609.6 -6.264051914,58.2374628007,609.6 -6.268160741,58.2406325289,609.6 -6.2728073901,58.2435886454,609.6 -6.2779522582,58.2463058737,609.6 -6.2835514515,58.2487609742,609.6 -6.2895571602,58.2509329449,609.6 -6.2959180678,58.2528032022,609.6 -6.3025797908,58.2543557411,609.6 -6.3094853477,58.2555772738,609.6 -6.3165756492,58.2564573442,609.6 -6.3237900087,58.2569884183,609.6 -6.3310666667,58.2571659496,609.6 + + + + + + EGRU801B STORNOWAY RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7961" txt_name="STORNOWAY RWY 06"><tr><td>581108N 0062422W -<br/>581136N 0062453W -<br/>581150N 0062406W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to<br/>581123N 0062333W -<br/>581108N 0062422W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.40615,58.1854555556,609.6 -6.3925569167,58.1896305556,609.6 -6.3959452388,58.1920382971,609.6 -6.3989963377,58.1945687406,609.6 -6.4016943056,58.1972087222,609.6 -6.4146805556,58.1932194444,609.6 -6.40615,58.1854555556,609.6 + + + + + + EGRU801C STORNOWAY RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7740" txt_name="STORNOWAY RWY 24"><tr><td>581434N 0061510W -<br/>581406N 0061439W -<br/>581351N 0061528W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to<br/>581420N 0061557W -<br/>581434N 0061510W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2528305556,58.2427805556,609.6 -6.2657381389,58.2388406389,609.6 -6.2627313236,58.236293013,609.6 -6.2600812359,58.2336375699,609.6 -6.2578016389,58.2308881667,609.6 -6.2442833333,58.2350138889,609.6 -6.2528305556,58.2427805556,609.6 + + + + + + EGRU801D STORNOWAY RWY 18 + <table border="1" cellpadding="1" cellspacing="0" row_id="7880" txt_name="STORNOWAY RWY 18"><tr><td>581607N 0062059W -<br/>581610N 0061958W -<br/>581526N 0061949W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to<br/>581523N 0062050W -<br/>581607N 0062059W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3497055556,58.2686027778,609.6 -6.3473553333,58.2562685833,609.6 -6.3417523051,58.2567821575,609.6 -6.3360935191,58.2570813209,609.6 -6.3304085,58.2571645,609.6 -6.3327527778,58.2694972222,609.6 -6.3497055556,58.2686027778,609.6 + + + + + + EGRU801E STORNOWAY RWY 36 + <table border="1" cellpadding="1" cellspacing="0" row_id="7904" txt_name="STORNOWAY RWY 36"><tr><td>580941N 0061844W -<br/>580938N 0061945W -<br/>581027N 0061954W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to<br/>581030N 0061853W -<br/>580941N 0061844W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3122833333,58.1615194444,609.6 -6.3148175,58.1749232778,609.6 -6.3204085528,58.1744109341,609.6 -6.3260548434,58.174112552,609.6 -6.3317271111,58.1740296944,609.6 -6.3291861111,58.1606222222,609.6 -6.3122833333,58.1615194444,609.6 + + + + + + EGRU802A WICK + <table border="1" cellpadding="1" cellspacing="0" row_id="8148" txt_name="WICK"><tr><td>A circle, 2 NM radius, centred at 582732N 0030535W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0930555556,58.4921426198,609.6 -3.0995859271,58.4919662053,609.6 -3.1060468805,58.4914388369,609.6 -3.1123697415,58.4905661205,609.6 -3.1184873162,58.4893573323,609.6 -3.1243346099,58.4878253192,609.6 -3.1298495226,58.4859863618,609.6 -3.1349735122,58.4838599997,609.6 -3.1396522186,58.4814688224,609.6 -3.1438360416,58.4788382279,609.6 -3.1474806671,58.4759961513,609.6 -3.1505475352,58.4729727663,609.6 -3.1530042459,58.4698001639,609.6 -3.1548248976,58.4665120097,609.6 -3.1559903559,58.4631431864,609.6 -3.1564884497,58.459729422,609.6 -3.1563140919,58.4563069112,609.6 -3.1554693256,58.4529119305,609.6 -3.153963294,58.4495804547,609.6 -3.1518121356,58.4463477753,609.6 -3.1490388059,58.4432481279,609.6 -3.1456728272,58.4403143306,609.6 -3.141749971,58.4375774374,609.6 -3.1373118745,58.4350664112,609.6 -3.1324055973,58.4328078191,609.6 -3.1270831219,58.4308255521,609.6 -3.1214008035,58.429140575,609.6 -3.1154187757,58.4277707055,609.6 -3.1092003171,58.4267304272,609.6 -3.1028111861,58.4260307381,609.6 -3.0963189308,58.4256790346,609.6 -3.0897921803,58.4256790346,609.6 -3.083299925,58.4260307381,609.6 -3.0769107941,58.4267304272,609.6 -3.0706923354,58.4277707055,609.6 -3.0647103076,58.429140575,609.6 -3.0590279892,58.4308255521,609.6 -3.0537055138,58.4328078191,609.6 -3.0487992366,58.4350664112,609.6 -3.0443611401,58.4375774374,609.6 -3.0404382839,58.4403143306,609.6 -3.0370723052,58.4432481279,609.6 -3.0342989755,58.4463477753,609.6 -3.0321478171,58.4495804547,609.6 -3.0306417855,58.4529119305,609.6 -3.0297970192,58.4563069112,609.6 -3.0296226614,58.459729422,609.6 -3.0301207552,58.4631431864,609.6 -3.0312862136,58.4665120097,609.6 -3.0331068652,58.4698001639,609.6 -3.0355635759,58.4729727663,609.6 -3.038630444,58.4759961513,609.6 -3.0422750695,58.4788382279,609.6 -3.0464588925,58.4814688224,609.6 -3.0511375989,58.4838599997,609.6 -3.0562615885,58.4859863618,609.6 -3.0617765012,58.4878253192,609.6 -3.0676237949,58.4893573323,609.6 -3.0737413696,58.4905661205,609.6 -3.0800642307,58.4914388369,609.6 -3.086525184,58.4919662053,609.6 -3.0930555556,58.4921426198,609.6 + + + + + + EGRU802B WICK RWY 13 + <table border="1" cellpadding="1" cellspacing="0" row_id="7795" txt_name="WICK RWY 13"><tr><td>582909N 0031033W -<br/>582935N 0030956W -<br/>582856N 0030818W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to<br/>582830N 0030855W -<br/>582909N 0031033W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.1757638889,58.4857583333,609.6 -3.1485312222,58.4750425556,609.6 -3.1455271826,58.4775976674,609.6 -3.1420951993,58.4800004426,609.6 -3.1382631667,58.4822312778,609.6 -3.16545,58.4929305556,609.6 -3.1757638889,58.4857583333,609.6 + + + + + + EGRU802C WICK RWY 31 + <table border="1" cellpadding="1" cellspacing="0" row_id="8175" txt_name="WICK RWY 31"><tr><td>582555N 0030040W -<br/>582529N 0030117W -<br/>582608N 0030253W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to<br/>582633N 0030216W -<br/>582555N 0030040W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-3.0110833333,58.4320166667,609.6 -3.0377739167,58.4425773056,609.6 -3.0408048412,58.4400322635,609.6 -3.0442604972,58.4376407495,609.6 -3.0481126944,58.4354221944,609.6 -3.021375,58.4248444444,609.6 -3.0110833333,58.4320166667,609.6 + + + + + + EGRU803A KIRKWALL + <table border="1" cellpadding="1" cellspacing="0" row_id="7810" txt_name="KIRKWALL"><tr><td>A circle, 2 NM radius, centred at 585729N 0025402W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9004805556,58.9912650259,609.6 -2.9071051505,58.9910886218,609.6 -2.9136593217,58.9905612849,609.6 -2.9200734005,58.9896886208,609.6 -2.9262792201,58.9884799056,609.6 -2.9322108453,58.9869479864,609.6 -2.9378052781,58.9851091435,609.6 -2.9430031308,58.9829829161,609.6 -2.9477492585,58.9805918934,609.6 -2.9519933464,58.9779614726,609.6 -2.9556904427,58.9751195881,609.6 -2.958801434,58.9720964125,609.6 -2.9612934561,58.9689240353,609.6 -2.9631402382,58.9656361206,609.6 -2.9643223745,58.9622675489,609.6 -2.9648275234,58.958854046,609.6 -2.9646505297,58.9554318039,609.6 -2.9637934711,58.9520370964,609.6 -2.9622656278,58.9487058948,609.6 -2.9600833753,58.9454734876,609.6 -2.9572700039,58.9423741067,609.6 -2.9538554649,58.9394405666,609.6 -2.9498760475,58.9367039177,609.6 -2.9453739904,58.9341931194,609.6 -2.9403970317,58.9319347351,609.6 -2.9349979022,58.9299526531,609.6 -2.9292337674,58.9282678349,609.6 -2.9231656248,58.9268980957,609.6 -2.9168576612,58.9258579171,609.6 -2.9103765784,58.9251582953,609.6 -2.9037908931,58.9248066258,609.6 -2.897170218,58.9248066258,609.6 -2.8905845327,58.9251582953,609.6 -2.8841034499,58.9258579171,609.6 -2.8777954863,58.9268980957,609.6 -2.8717273437,58.9282678349,609.6 -2.8659632089,58.9299526531,609.6 -2.8605640794,58.9319347351,609.6 -2.8555871207,58.9341931194,609.6 -2.8510850636,58.9367039177,609.6 -2.8471056462,58.9394405666,609.6 -2.8436911072,58.9423741067,609.6 -2.8408777358,58.9454734876,609.6 -2.8386954833,58.9487058948,609.6 -2.83716764,58.9520370964,609.6 -2.8363105814,58.9554318039,609.6 -2.8361335877,58.958854046,609.6 -2.8366387366,58.9622675489,609.6 -2.8378208729,58.9656361206,609.6 -2.839667655,58.9689240353,609.6 -2.8421596771,58.9720964125,609.6 -2.8452706684,58.9751195881,609.6 -2.8489677647,58.9779614726,609.6 -2.8532118526,58.9805918934,609.6 -2.8579579804,58.9829829161,609.6 -2.863155833,58.9851091435,609.6 -2.8687502658,58.9869479864,609.6 -2.874681891,58.9884799056,609.6 -2.8808877106,58.9896886208,609.6 -2.8873017895,58.9905612849,609.6 -2.8938559607,58.9910886218,609.6 -2.9004805556,58.9912650259,609.6 + + + + + + EGRU803B KIRKWALL RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8179" txt_name="KIRKWALL RWY 09"><tr><td>585704N 0025947W -<br/>585737N 0025950W -<br/>585740N 0025753W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to<br/>585707N 0025750W -<br/>585704N 0025947W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9965222222,58.9512361111,609.6 -2.9637882778,58.9520225,609.6 -2.9645786005,58.9549946584,609.6 -2.9648472588,58.9579915212,609.6 -2.9645919444,58.9609886944,609.6 -2.9973055556,58.9602027778,609.6 -2.9965222222,58.9512361111,609.6 + + + + + + EGRU803C KIRKWALL RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7815" txt_name="KIRKWALL RWY 27"><tr><td>585753N 0024808W -<br/>585721N 0024806W -<br/>585718N 0025011W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to<br/>585750N 0025014W -<br/>585753N 0024808W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8023416667,58.9647638889,609.6 -2.8371498056,58.9639711944,609.6 -2.8363708043,58.9609981919,609.6 -2.836113826,58.9580010211,609.6 -2.8363808333,58.9550040833,609.6 -2.8015527778,58.9557972222,609.6 -2.8023416667,58.9647638889,609.6 + + + + + + EGRU803D KIRKWALL RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="7532" txt_name="KIRKWALL RWY 14"><tr><td>585932N 0025817W -<br/>585953N 0025729W -<br/>585907N 0025615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to<br/>585845N 0025701W -<br/>585932N 0025817W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.9713833333,58.9922083333,609.6 -2.9502969444,58.9790798333,609.6 -2.9464099969,58.9813176402,609.6 -2.9421470098,58.9833649721,609.6 -2.9375428056,58.9852050556,609.6 -2.9579805556,58.9979333333,609.6 -2.9713833333,58.9922083333,609.6 + + + + + + EGRU803E KIRKWALL RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="8076" txt_name="KIRKWALL RWY 32"><tr><td>585530N 0025028W -<br/>585509N 0025116W -<br/>585544N 0025211W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to<br/>585603N 0025121W -<br/>585530N 0025028W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.8410083333,58.9249138889,609.6 -2.8557253611,58.9341237778,609.6 -2.8600814518,58.9321339146,609.6 -2.8647667919,58.9303553359,609.6 -2.8697431389,58.9288025278,609.6 -2.8543805556,58.9191916667,609.6 -2.8410083333,58.9249138889,609.6 + + + + + + EGRU901A TRESCO + <table border="1" cellpadding="1" cellspacing="0" row_id="7780" txt_name="TRESCO"><tr><td>A circle, 2 NM radius, centred at 495644N 0061955W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 </td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3318986389,49.9787758952,609.6 -6.3372082978,49.9785992755,609.6 -6.3424615574,49.9780712925,609.6 -6.3476026213,49.9771975541,609.6 -6.3525768918,49.9759873407,609.6 -6.3573315533,49.9744535052,609.6 -6.3618161354,49.9726123364,609.6 -6.3659830515,49.9704833849,609.6 -6.3697881047,49.9680892542,609.6 -6.3731909576,49.9654553598,609.6 -6.3761555602,49.9626096581,609.6 -6.3786505308,49.9595823487,609.6 -6.3806494871,49.9564055526,609.6 -6.3821313228,49.9531129705,609.6 -6.3830804283,49.9497395243,609.6 -6.3834868512,49.9463209866,609.6 -6.3833463981,49.9428936002,609.6 -6.3826606734,49.9394936945,609.6 -6.3814370581,49.9361572996,609.6 -6.3796886263,49.9329197657,609.6 -6.3774340024,49.9298153883,609.6 -6.3746971601,49.9268770461,609.6 -6.3715071648,49.9241358536,609.6 -6.3678978635,49.9216208323,609.6 -6.3639075243,49.9193586054,609.6 -6.3595784308,49.9173731162,609.6 -6.3549564343,49.9156853764,609.6 -6.3500904696,49.9143132447,609.6 -6.3450320383,49.913271239,609.6 -6.3398346667,49.9125703833,609.6 -6.3345533424,49.9122180921,609.6 -6.3292439354,49.9122180921,609.6 -6.323962611,49.9125703833,609.6 -6.3187652395,49.913271239,609.6 -6.3137068082,49.9143132447,609.6 -6.3088408435,49.9156853764,609.6 -6.304218847,49.9173731162,609.6 -6.2998897535,49.9193586054,609.6 -6.2958994143,49.9216208323,609.6 -6.2922901129,49.9241358536,609.6 -6.2891001177,49.9268770461,609.6 -6.2863632754,49.9298153883,609.6 -6.2841086515,49.9329197657,609.6 -6.2823602197,49.9361572996,609.6 -6.2811366044,49.9394936945,609.6 -6.2804508797,49.9428936002,609.6 -6.2803104265,49.9463209866,609.6 -6.2807168495,49.9497395243,609.6 -6.2816659549,49.9531129705,609.6 -6.2831477907,49.9564055526,609.6 -6.285146747,49.9595823487,609.6 -6.2876417176,49.9626096581,609.6 -6.2906063202,49.9654553598,609.6 -6.2940091731,49.9680892542,609.6 -6.2978142263,49.9704833849,609.6 -6.3019811424,49.9726123364,609.6 -6.3064657245,49.9744535052,609.6 -6.311220386,49.9759873407,609.6 -6.3161946565,49.9771975541,609.6 -6.3213357204,49.9780712925,609.6 -6.32658898,49.9785992755,609.6 -6.3318986389,49.9787758952,609.6 + + + + + + EGRU902A SCILLY ISLES/ST MARY'S + <table border="1" cellpadding="1" cellspacing="0" row_id="8156" txt_name="SCILLY ISLES/ST MARY'S"><tr><td>A circle, 2 NM radius, centred at 495448N 0061730W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2917583333,49.9465871643,609.6 -6.297064453,49.9464105438,609.6 -6.3023142112,49.9458825582,609.6 -6.3074518487,49.9450088157,609.6 -6.3124228043,49.9437985963,609.6 -6.3171742977,49.9422647534,609.6 -6.3216558924,49.9404235756,609.6 -6.3258200333,49.9382946135,609.6 -6.3296225531,49.9359004707,609.6 -6.3330231412,49.933266563,609.6 -6.3359857716,49.9304208467,609.6 -6.3384790834,49.9273935215,609.6 -6.3404767119,49.9242167086,609.6 -6.3419575646,49.9209241088,609.6 -6.342906042,49.9175506443,609.6 -6.3433121985,49.9141320877,609.6 -6.343171843,49.9107046821,609.6 -6.3424865789,49.9073047571,609.6 -6.341263782,49.903968343,609.6 -6.3395165174,49.9007307902,609.6 -6.3372633973,49.8976263944,609.6 -6.3345283791,49.8946880347,609.6 -6.3313405088,49.8919468255,609.6 -6.3277336107,49.8894317889,609.6 -6.3237459277,49.887169548,609.6 -6.319419715,49.8851840465,609.6 -6.3148007936,49.8834962961,609.6 -6.3099380657,49.8821241558,609.6 -6.3048829988,49.8810821435,609.6 -6.2996890837,49.8803812834,609.6 -6.2944112715,49.8800289899,609.6 -6.2891053952,49.8800289899,609.6 -6.283827583,49.8803812834,609.6 -6.2786336679,49.8810821435,609.6 -6.273578601,49.8821241558,609.6 -6.268715873,49.8834962961,609.6 -6.2640969517,49.8851840465,609.6 -6.259770739,49.887169548,609.6 -6.2557830559,49.8894317889,609.6 -6.2521761579,49.8919468255,609.6 -6.2489882876,49.8946880347,609.6 -6.2462532693,49.8976263944,609.6 -6.2440001492,49.9007307902,609.6 -6.2422528847,49.903968343,609.6 -6.2410300877,49.9073047571,609.6 -6.2403448236,49.9107046821,609.6 -6.2402044682,49.9141320877,609.6 -6.2406106246,49.9175506443,609.6 -6.2415591021,49.9209241088,609.6 -6.2430399548,49.9242167086,609.6 -6.2450375832,49.9273935215,609.6 -6.2475308951,49.9304208467,609.6 -6.2504935255,49.933266563,609.6 -6.2538941136,49.9359004707,609.6 -6.2576966333,49.9382946135,609.6 -6.2618607743,49.9404235756,609.6 -6.2663423689,49.9422647534,609.6 -6.2710938623,49.9437985963,609.6 -6.276064818,49.9450088157,609.6 -6.2812024554,49.9458825582,609.6 -6.2864522136,49.9464105438,609.6 -6.2917583333,49.9465871643,609.6 + + + + + + EGRU902B SCILLY ISLES/ST MARY'S RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="8122" txt_name="SCILLY ISLES/ST MARY'S RWY 09"><tr><td>495423N 0062152W -<br/>495456N 0062155W -<br/>495458N 0062035W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to<br/>495426N 0062033W -<br/>495423N 0062152W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3645694444,49.9064916667,609.6 -6.34246425,49.9072264167,609.6 -6.3431052792,49.9102031456,609.6 -6.3433281924,49.9132050721,609.6 -6.3431310833,49.91620775,609.6 -6.3652722222,49.9154722222,609.6 -6.3645694444,49.9064916667,609.6 + + + + + + EGRU902C SCILLY ISLES/ST MARY'S RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7748" txt_name="SCILLY ISLES/ST MARY'S RWY 27"><tr><td>495513N 0061309W -<br/>495441N 0061307W -<br/>495438N 0061425W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to<br/>495510N 0061428W -<br/>495513N 0061309W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2192583333,49.9202444444,609.6 -6.2411032222,49.9195422222,609.6 -6.2404376283,49.9165683712,609.6 -6.2401899616,49.9135678841,609.6 -6.2403621389,49.9105651944,609.6 -6.2185527778,49.9112666667,609.6 -6.2192583333,49.9202444444,609.6 + + + + + + EGRU902D SCILLY ISLES/ST MARY'S RWY 14 + <table border="1" cellpadding="1" cellspacing="0" row_id="8159" txt_name="SCILLY ISLES/ST MARY'S RWY 14"><tr><td>495647N 0062042W -<br/>495709N 0062004W -<br/>495629N 0061911W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to<br/>495607N 0061949W -<br/>495647N 0062042W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.3451222222,49.946525,609.6 -6.3303235833,49.9354010833,609.6 -6.3270783713,49.9375560717,609.6 -6.3235450932,49.9395133576,609.6 -6.3197525278,49.9412569722,609.6 -6.3345444444,49.9523777778,609.6 -6.3451222222,49.946525,609.6 + + + + + + EGRU902E SCILLY ISLES/ST MARY'S RWY 32 + <table border="1" cellpadding="1" cellspacing="0" row_id="7586" txt_name="SCILLY ISLES/ST MARY'S RWY 32"><tr><td>495248N 0061419W -<br/>495227N 0061457W -<br/>495307N 0061550W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to<br/>495328N 0061512W -<br/>495248N 0061419W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-6.2384777778,49.8800277778,609.6 -6.2532298056,49.8911571944,609.6 -6.2564752205,49.8890044172,609.6 -6.2600075139,49.8870493107,609.6 -6.2637979444,49.8853077778,609.6 -6.2490388889,49.874175,609.6 -6.2384777778,49.8800277778,609.6 + + + + + + EGRU903A EDAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7864" txt_name="EDAY"><tr><td>A circle, 2 NM radius, centred at 591125N 0024621W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.7724055556,59.2236221598,609.6 -2.7790751247,59.2234457605,609.6 -2.7856737902,59.2229184379,609.6 -2.7921314086,59.2220457978,609.6 -2.7983793486,59.2208371162,609.6 -2.8043512262,59.2193052401,609.6 -2.8099836148,59.2174664497,609.6 -2.8152167228,59.2153402842,609.6 -2.8199950311,59.2129493325,609.6 -2.8242678836,59.2103189917,609.6 -2.8279900241,59.2074771956,609.6 -2.831122075,59.2044541165,609.6 -2.8336309507,59.2012818432,609.6 -2.835490204,59.1979940389,609.6 -2.8366802999,59.1946255834,609.6 -2.8371888152,59.1912122014,609.6 -2.8370105624,59.1877900836,609.6 -2.8361476357,59.1843955025,609.6 -2.8346093806,59.181064428,609.6 -2.832412286,59.1778321468,609.6 -2.8295798019,59.1747328895,609.6 -2.8261420844,59.1717994687,609.6 -2.8221356698,59.1690629331,609.6 -2.8176030839,59.1665522406,609.6 -2.8125923887,59.1642939529,609.6 -2.8071566721,59.1623119567,609.6 -2.8013534865,59.1606272124,609.6 -2.7952442416,59.1592575338,609.6 -2.7888935577,59.1582174015,609.6 -2.7823685869,59.1575178111,609.6 -2.7757383079,59.1571661574,609.6 -2.7690728032,59.1571661574,609.6 -2.7624425242,59.1575178111,609.6 -2.7559175534,59.1582174015,609.6 -2.7495668695,59.1592575338,609.6 -2.7434576246,59.1606272124,609.6 -2.737654439,59.1623119567,609.6 -2.7322187224,59.1642939529,609.6 -2.7272080272,59.1665522406,609.6 -2.7226754413,59.1690629331,609.6 -2.7186690267,59.1717994687,609.6 -2.7152313092,59.1747328895,609.6 -2.7123988252,59.1778321468,609.6 -2.7102017305,59.181064428,609.6 -2.7086634754,59.1843955025,609.6 -2.7078005487,59.1877900836,609.6 -2.7076222959,59.1912122014,609.6 -2.7081308112,59.1946255834,609.6 -2.7093209071,59.1979940389,609.6 -2.7111801604,59.2012818432,609.6 -2.7136890362,59.2044541165,609.6 -2.716821087,59.2074771956,609.6 -2.7205432276,59.2103189917,609.6 -2.72481608,59.2129493325,609.6 -2.7295943883,59.2153402842,609.6 -2.7348274963,59.2174664497,609.6 -2.7404598849,59.2193052401,609.6 -2.7464317625,59.2208371162,609.6 -2.7526797025,59.2220457978,609.6 -2.7591373209,59.2229184379,609.6 -2.7657359864,59.2234457605,609.6 -2.7724055556,59.2236221598,609.6 + + + + + + EGRU904A STRONSAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7677" txt_name="STRONSAY"><tr><td>A circle, 2 NM radius, centred at 590919N 0023830W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.6415277778,59.1885278961,609.6 -2.648190508,59.1883514961,609.6 -2.6547824075,59.1878241714,609.6 -2.6612334051,59.1869515277,609.6 -2.6674749401,59.1857428411,609.6 -2.6734406968,59.1842109585,609.6 -2.6790673137,59.1823721602,609.6 -2.6842950607,59.1802459854,609.6 -2.6890684755,59.177855023,609.6 -2.6933369539,59.1752246701,609.6 -2.6970552861,59.1723828607,609.6 -2.7001841346,59.1693597671,609.6 -2.7026904476,59.1661874781,609.6 -2.7045478046,59.1628996572,609.6 -2.7057366901,59.1595311842,609.6 -2.7062446936,59.156117784,609.6 -2.7060666323,59.1526956474,609.6 -2.7052045979,59.1493010472,609.6 -2.7036679261,59.1459699536,609.6 -2.7014730884,59.1427376534,609.6 -2.6986435108,59.1396383774,609.6 -2.6952093178,59.1367049386,609.6 -2.6912070085,59.1339683859,609.6 -2.686679065,59.1314576774,609.6 -2.6816734998,59.1291993752,609.6 -2.6762433467,59.1272173661,609.6 -2.6704460993,59.1255326105,609.6 -2.6643431045,59.1241629228,609.6 -2.6579989168,59.1231227835,609.6 -2.6514806197,59.1224231884,609.6 -2.6448571217,59.1220715323,609.6 -2.6381984339,59.1220715323,609.6 -2.6315749359,59.1224231884,609.6 -2.6250566388,59.1231227835,609.6 -2.618712451,59.1241629228,609.6 -2.6126094562,59.1255326105,609.6 -2.6068122088,59.1272173661,609.6 -2.6013820557,59.1291993752,609.6 -2.5963764906,59.1314576774,609.6 -2.591848547,59.1339683859,609.6 -2.5878462377,59.1367049386,609.6 -2.5844120448,59.1396383774,609.6 -2.5815824671,59.1427376534,609.6 -2.5793876295,59.1459699536,609.6 -2.5778509576,59.1493010472,609.6 -2.5769889233,59.1526956474,609.6 -2.576810862,59.156117784,609.6 -2.5773188654,59.1595311842,609.6 -2.578507751,59.1628996572,609.6 -2.5803651079,59.1661874781,609.6 -2.5828714209,59.1693597671,609.6 -2.5860002694,59.1723828607,609.6 -2.5897186017,59.1752246701,609.6 -2.5939870801,59.177855023,609.6 -2.5987604949,59.1802459854,609.6 -2.6039882418,59.1823721602,609.6 -2.6096148588,59.1842109585,609.6 -2.6155806155,59.1857428411,609.6 -2.6218221505,59.1869515277,609.6 -2.6282731481,59.1878241714,609.6 -2.6348650476,59.1883514961,609.6 -2.6415277778,59.1885278961,609.6 + + + + + + EGRU905A SANDAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7503" txt_name="SANDAY"><tr><td>A circle, 2 NM radius, centred at 591501N 0023430W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.575,59.2834190741,609.6 -2.5816812603,59.2832426761,609.6 -2.5882914921,59.2827153572,609.6 -2.5947604287,59.2818427233,609.6 -2.601019318,59.2806340502,609.6 -2.6070016592,59.2791021852,609.6 -2.6126439145,59.2772634082,609.6 -2.6178861871,59.2751372585,609.6 -2.6226728607,59.272746325,609.6 -2.6269531904,59.2701160047,609.6 -2.6306818411,59.2672742313,609.6 -2.6338193664,59.2642511769,609.6 -2.6363326231,59.2610789301,609.6 -2.6381951183,59.2577911543,609.6 -2.6393872831,59.2544227286,609.6 -2.6398966734,59.2510093776,609.6 -2.6397180932,59.2475872917,609.6 -2.638853641,59.244192743,609.6 -2.6373126792,59.2408617011,609.6 -2.6351117263,59.2376294523,609.6 -2.6322742739,59.2345302267,609.6 -2.628830531,59.2315968366,609.6 -2.6248170985,59.2288603301,609.6 -2.6202765767,59.2263496648,609.6 -2.6152571117,59.224091402,609.6 -2.6098118844,59.2221094279,609.6 -2.6039985477,59.2204247025,609.6 -2.5978786183,59.2190550394,609.6 -2.5915168294,59.2180149191,609.6 -2.58498045,59.2173153368,609.6 -2.578338579,59.2169636871,609.6 -2.571661421,59.2169636871,609.6 -2.56501955,59.2173153368,609.6 -2.5584831706,59.2180149191,609.6 -2.5521213817,59.2190550394,609.6 -2.5460014523,59.2204247025,609.6 -2.5401881156,59.2221094279,609.6 -2.5347428883,59.224091402,609.6 -2.5297234233,59.2263496648,609.6 -2.5251829015,59.2288603301,609.6 -2.521169469,59.2315968366,609.6 -2.5177257261,59.2345302267,609.6 -2.5148882737,59.2376294523,609.6 -2.5126873208,59.2408617011,609.6 -2.511146359,59.244192743,609.6 -2.5102819068,59.2475872917,609.6 -2.5101033266,59.2510093776,609.6 -2.5106127169,59.2544227286,609.6 -2.5118048817,59.2577911543,609.6 -2.5136673769,59.2610789301,609.6 -2.5161806336,59.2642511769,609.6 -2.5193181589,59.2672742313,609.6 -2.5230468096,59.2701160047,609.6 -2.5273271393,59.272746325,609.6 -2.5321138129,59.2751372585,609.6 -2.5373560855,59.2772634082,609.6 -2.5429983408,59.2791021852,609.6 -2.548980682,59.2806340502,609.6 -2.5552395713,59.2818427233,609.6 -2.5617085079,59.2827153572,609.6 -2.5683187397,59.2832426761,609.6 -2.575,59.2834190741,609.6 + + + + + + EGRU906A NORTH RONALDSAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7537" txt_name="NORTH RONALDSAY"><tr><td>A circle, 2 NM radius, centred at 592203N 0022605W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.4346972222,59.4008184708,609.6 -2.4414015769,59.4006420752,609.6 -2.4480346567,59.4001147635,609.6 -2.454525951,59.3992421415,609.6 -2.4608064692,59.3980334853,609.6 -2.4668094801,59.3965016417,609.6 -2.4724712256,59.3946628911,609.6 -2.4777316019,59.3925367724,609.6 -2.4825348001,59.3901458745,609.6 -2.4868299002,59.3875155943,609.6 -2.4905714109,59.3846738652,609.6 -2.4937197499,59.3816508592,609.6 -2.4962416607,59.3784786646,609.6 -2.4981105595,59.3751909442,609.6 -2.4993068112,59.3718225769,609.6 -2.4998179299,59.3684092867,609.6 -2.4996387027,59.3649872634,609.6 -2.4987712369,59.3615927783,609.6 -2.4972249285,59.3582618004,609.6 -2.4950163539,59.3550296151,609.6 -2.492169087,59.3519304518,609.6 -2.4887134419,59.3489971217,609.6 -2.4846861463,59.3462606725,609.6 -2.4801299481,59.3437500605,609.6 -2.4750931596,59.3414918463,609.6 -2.4696291451,59.3395099156,609.6 -2.4637957561,59.3378252275,609.6 -2.457654721,59.336455595,609.6 -2.4512709957,59.3354154981,609.6 -2.4447120802,59.3347159315,609.6 -2.438047311,59.3343642899,609.6 -2.4313471335,59.3343642899,609.6 -2.4246823642,59.3347159315,609.6 -2.4181234487,59.3354154981,609.6 -2.4117397234,59.336455595,609.6 -2.4055986884,59.3378252275,609.6 -2.3997652994,59.3395099156,609.6 -2.3943012849,59.3414918463,609.6 -2.3892644964,59.3437500605,609.6 -2.3847082982,59.3462606725,609.6 -2.3806810026,59.3489971217,609.6 -2.3772253575,59.3519304518,609.6 -2.3743780906,59.3550296151,609.6 -2.372169516,59.3582618004,609.6 -2.3706232075,59.3615927783,609.6 -2.3697557417,59.3649872634,609.6 -2.3695765146,59.3684092867,609.6 -2.3700876332,59.3718225769,609.6 -2.3712838849,59.3751909442,609.6 -2.3731527837,59.3784786646,609.6 -2.3756746945,59.3816508592,609.6 -2.3788230336,59.3846738652,609.6 -2.3825645443,59.3875155943,609.6 -2.3868596444,59.3901458745,609.6 -2.3916628426,59.3925367724,609.6 -2.3969232188,59.3946628911,609.6 -2.4025849643,59.3965016417,609.6 -2.4085879752,59.3980334853,609.6 -2.4148684935,59.3992421415,609.6 -2.4213597877,59.4001147635,609.6 -2.4279928675,59.4006420752,609.6 -2.4346972222,59.4008184708,609.6 + + + + + + EGRU907A FAIR ISLE + <table border="1" cellpadding="1" cellspacing="0" row_id="7982" txt_name="FAIR ISLE"><tr><td>A circle, 2 NM radius, centred at 593205N 0013743W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.6285111111,59.5679759474,609.6 -1.6352486751,59.5677995552,609.6 -1.6419146096,59.5672722537,609.6 -1.6484380536,59.5663996487,609.6 -1.6547496737,59.5651910162,609.6 -1.660782407,59.5636592032,609.6 -1.6664721789,59.5618204898,609.6 -1.6717585875,59.559694415,609.6 -1.6765855474,59.5573035675,609.6 -1.6809018868,59.554673344,609.6 -1.6846618895,59.5518316778,609.6 -1.6878257782,59.5488087405,609.6 -1.6903601329,59.5456366198,609.6 -1.6922382397,59.5423489782,609.6 -1.6934403679,59.5389806938,609.6 -1.6939539715,59.5355674899,609.6 -1.6937738138,59.5321455553,609.6 -1.6929020143,59.5287511606,609.6 -1.6913480172,59.5254202735,609.6 -1.6891284828,59.5221881786,609.6 -1.6862671028,59.5190891037,609.6 -1.6827943426,59.5161558591,609.6 -1.6787471124,59.5134194912,609.6 -1.674168372,59.510908955,609.6 -1.669106673,59.5086508102,609.6 -1.6636156433,59.5066689411,609.6 -1.6577534201,59.504984306,609.6 -1.6515820362,59.503614717,609.6 -1.6451667673,59.5025746534,609.6 -1.6385754462,59.5018751093,609.6 -1.6318777503,59.501523479,609.6 -1.6251444719,59.501523479,609.6 -1.6184467761,59.5018751093,609.6 -1.6118554549,59.5025746534,609.6 -1.605440186,59.503614717,609.6 -1.5992688021,59.504984306,609.6 -1.5934065789,59.5066689411,609.6 -1.5879155492,59.5086508102,609.6 -1.5828538502,59.510908955,609.6 -1.5782751099,59.5134194912,609.6 -1.5742278797,59.5161558591,609.6 -1.5707551194,59.5190891037,609.6 -1.5678937394,59.5221881786,609.6 -1.565674205,59.5254202735,609.6 -1.5641202079,59.5287511606,609.6 -1.5632484084,59.5321455553,609.6 -1.5630682507,59.5355674899,609.6 -1.5635818543,59.5389806938,609.6 -1.5647839825,59.5423489782,609.6 -1.5666620893,59.5456366198,609.6 -1.569196444,59.5488087405,609.6 -1.5723603328,59.5518316778,609.6 -1.5761203355,59.554673344,609.6 -1.5804366748,59.5573035675,609.6 -1.5852636348,59.559694415,609.6 -1.5905500433,59.5618204898,609.6 -1.5962398152,59.5636592032,609.6 -1.6022725485,59.5651910162,609.6 -1.6085841686,59.5663996487,609.6 -1.6151076126,59.5672722537,609.6 -1.6217735472,59.5677995552,609.6 -1.6285111111,59.5679759474,609.6 + + + + + + EGRU908A SUMBURGH + <table border="1" cellpadding="1" cellspacing="0" row_id="7802" txt_name="SUMBURGH"><tr><td>A circle, 2 NM radius, centred at 595253N 0011738W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2938289167,59.9147235403,609.6 -1.3006366179,59.914547155,609.6 -1.3073719411,59.9140198744,609.6 -1.3139632846,59.9131473042,609.6 -1.3203405909,59.9119387204,609.6 -1.3264360969,59.91040697,609.6 -1.3321850596,59.908568333,609.6 -1.3375264472,59.9064423484,609.6 -1.3424035907,59.9040516045,609.6 -1.346764786,59.9014214977,609.6 -1.3505638424,59.8985799609,609.6 -1.3537605706,59.8955571648,609.6 -1.3563212053,59.8923851965,609.6 -1.3582187579,59.8890977171,609.6 -1.3594332958,59.8857296036,609.6 -1.3599521463,59.8823165777,609.6 -1.3597700222,59.8788948264,609.6 -1.3588890691,59.8755006183,609.6 -1.3573188329,59.8721699191,609.6 -1.3550761509,59.8689380107,609.6 -1.3521849641,59.8658391189,609.6 -1.3486760571,59.8629060512,609.6 -1.3445867258,59.8601698514,609.6 -1.3399603776,59.8576594723,609.6 -1.3348460691,59.855401471,609.6 -1.3292979853,59.8534197296,609.6 -1.3233748663,59.8517352043,609.6 -1.317139388,59.8503657054,609.6 -1.310657502,59.8493257108,609.6 -1.3039977428,59.8486262133,609.6 -1.2972305088,59.8482746066,609.6 -1.2904273245,59.8482746066,609.6 -1.2836600906,59.8486262133,609.6 -1.2770003314,59.8493257108,609.6 -1.2705184453,59.8503657054,609.6 -1.264282967,59.8517352043,609.6 -1.258359848,59.8534197296,609.6 -1.2528117642,59.855401471,609.6 -1.2476974557,59.8576594723,609.6 -1.2430711075,59.8601698514,609.6 -1.2389817762,59.8629060512,609.6 -1.2354728692,59.8658391189,609.6 -1.2325816824,59.8689380107,609.6 -1.2303390004,59.8721699191,609.6 -1.2287687643,59.8755006183,609.6 -1.2278878111,59.8788948264,609.6 -1.227705687,59.8823165777,609.6 -1.2282245375,59.8857296036,609.6 -1.2294390754,59.8890977171,609.6 -1.231336628,59.8923851965,609.6 -1.2338972627,59.8955571648,609.6 -1.237093991,59.8985799609,609.6 -1.2408930474,59.9014214977,609.6 -1.2452542426,59.9040516045,609.6 -1.2501313861,59.9064423484,609.6 -1.2554727738,59.908568333,609.6 -1.2612217364,59.91040697,609.6 -1.2673172424,59.9119387204,609.6 -1.2736945487,59.9131473042,609.6 -1.2802858923,59.9140198744,609.6 -1.2870212155,59.914547155,609.6 -1.2938289167,59.9147235403,609.6 + + + + + + EGRU908B SUMBURGH RWY 06 + <table border="1" cellpadding="1" cellspacing="0" row_id="7783" txt_name="SUMBURGH RWY 06"><tr><td>595040N 0012125W -<br/>595106N 0012203W -<br/>595137N 0012040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595114N 0011952W -<br/>595040N 0012125W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3568085833,59.8444108056,609.6 -1.3311036389,59.8540180556,609.6 -1.3359630795,59.8558562601,609.6 -1.3404666687,59.8579111898,609.6 -1.3445763333,59.8601654722,609.6 -1.3674341667,59.8516208056,609.6 -1.3568085833,59.8444108056,609.6 + + + + + + EGRU908C SUMBURGH RWY 24 + <table border="1" cellpadding="1" cellspacing="0" row_id="7855" txt_name="SUMBURGH RWY 24"><tr><td>595429N 0011258W -<br/>595403N 0011220W -<br/>595329N 0011351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595359N 0011419W -<br/>595429N 0011258W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.2162301667,59.9079886667,609.6 -1.2384997778,59.8997096111,609.6 -1.2354006971,59.897077012,609.6 -1.2327967446,59.8943124159,609.6 -1.2307098611,59.89143925,609.6 -1.2055865833,59.9007787222,609.6 -1.2162301667,59.9079886667,609.6 + + + + + + EGRU908D SUMBURGH RWY 09 + <table border="1" cellpadding="1" cellspacing="0" row_id="7887" txt_name="SUMBURGH RWY 09"><tr><td>595217N 0012335W -<br/>595249N 0012342W -<br/>595256N 0012136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595224N 0012129W -<br/>595217N 0012335W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3929947222,59.87130875,609.6 -1.3579365,59.8733186944,609.6 -1.3591408487,59.8762570415,609.6 -1.359813575,59.8792380001,609.6 -1.3599490556,59.8822373056,609.6 -1.3949956111,59.8802280556,609.6 -1.3929947222,59.87130875,609.6 + + + + + + EGRU908E SUMBURGH RWY 27 + <table border="1" cellpadding="1" cellspacing="0" row_id="7601" txt_name="SUMBURGH RWY 27"><tr><td>595330N 0011140W -<br/>595258N 0011133W -<br/>595251N 0011340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595323N 0011347W -<br/>595330N 0011140W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.19437,59.8916009167,609.6 -1.2296873611,59.8896215833,609.6 -1.2284900505,59.8866824629,609.6 -1.2278249785,59.8837010623,609.6 -1.2276974167,59.8807016667,609.6 -1.1923684444,59.8826816389,609.6 -1.19437,59.8916009167,609.6 + + + + + + EGRU908F SUMBURGH RWY 15 + <table border="1" cellpadding="1" cellspacing="0" row_id="8015" txt_name="SUMBURGH RWY 15"><tr><td>595450N 0012132W -<br/>595509N 0012041W -<br/>595434N 0011948W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595412N 0012037W -<br/>595450N 0012132W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.3589489444,59.9138691667,609.6 -1.3434973056,59.9034362778,609.6 -1.3393430101,59.9056034287,609.6 -1.3348151617,59.9075729269,609.6 -1.3299508611,59.9093286111,609.6 -1.34459625,59.9192197778,609.6 -1.3589489444,59.9138691667,609.6 + + + + + + EGRU908G SUMBURGH RWY 33 + <table border="1" cellpadding="1" cellspacing="0" row_id="7953" txt_name="SUMBURGH RWY 33"><tr><td>595022N 0011337W -<br/>595003N 0011429W -<br/>595104N 0011559W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to<br/>595122N 0011504W -<br/>595022N 0011337W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-1.226986,59.8395753611,609.6 -1.2512414722,59.8560408056,609.6 -1.2559873152,59.8542101142,609.6 -1.2610422146,59.8526025447,609.6 -1.2663648333,59.8512312222,609.6 -1.2413044167,59.8342246667,609.6 -1.226986,59.8395753611,609.6 + + + + + + EGRU909A WESTRAY + <table border="1" cellpadding="1" cellspacing="0" row_id="7771" txt_name="WESTRAY"><tr><td>A circle, 2 NM radius, centred at 592100N 0025700W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.949875,59.3832852275,609.6 -2.9565758937,59.3831088315,609.6 -2.9632055494,59.3825815187,609.6 -2.969693493,59.381708895,609.6 -2.9759707698,59.3805002362,609.6 -2.9819706831,59.3789683895,609.6 -2.9876295077,59.3771296349,609.6 -2.9928871709,59.3750035117,609.6 -2.9976878926,59.3726126084,609.6 -3.0019807792,59.3699823222,609.6 -3.0057203627,59.3671405865,609.6 -3.0088670811,59.3641175733,609.6 -3.011387695,59.3609453709,609.6 -3.0132556341,59.3576576423,609.6 -3.0144512734,59.3542892663,609.6 -3.014962133,59.350875967,609.6 -3.0147830028,59.3474539343,609.6 -3.0139159887,59.3440594397,609.6 -3.0123704815,59.3407284522,609.6 -3.0101630491,59.3374962575,609.6 -3.0073172531,59.3343970849,609.6 -3.0038633917,59.3314637459,609.6 -2.9998381737,59.3287272881,609.6 -2.9952843248,59.3262166681,609.6 -2.9902501325,59.3239584467,609.6 -2.9847889335,59.3219765095,609.6 -2.9789585496,59.3202918158,609.6 -2.9728206775,59.3189221788,609.6 -2.9664402396,59.3178820784,609.6 -2.9598847015,59.3171825094,609.6 -2.9532233639,59.3168308666,609.6 -2.9465266361,59.3168308666,609.6 -2.9398652985,59.3171825094,609.6 -2.9333097604,59.3178820784,609.6 -2.9269293225,59.3189221788,609.6 -2.9207914504,59.3202918158,609.6 -2.9149610665,59.3219765095,609.6 -2.9094998675,59.3239584467,609.6 -2.9044656752,59.3262166681,609.6 -2.8999118263,59.3287272881,609.6 -2.8958866083,59.3314637459,609.6 -2.8924327469,59.3343970849,609.6 -2.8895869509,59.3374962575,609.6 -2.8873795185,59.3407284522,609.6 -2.8858340113,59.3440594397,609.6 -2.8849669972,59.3474539343,609.6 -2.884787867,59.350875967,609.6 -2.8852987266,59.3542892663,609.6 -2.8864943659,59.3576576423,609.6 -2.888362305,59.3609453709,609.6 -2.8908829189,59.3641175733,609.6 -2.8940296373,59.3671405865,609.6 -2.8977692208,59.3699823222,609.6 -2.9020621074,59.3726126084,609.6 -2.9068628291,59.3750035117,609.6 -2.9121204923,59.3771296349,609.6 -2.9177793169,59.3789683895,609.6 -2.9237792302,59.3805002362,609.6 -2.930056507,59.381708895,609.6 -2.9365444506,59.3825815187,609.6 -2.9431741063,59.3831088315,609.6 -2.949875,59.3832852275,609.6 + + + + + + EGRU910A PAPA WESTRAY + <table border="1" cellpadding="1" cellspacing="0" row_id="8023" txt_name="PAPA WESTRAY"><tr><td>A circle, 2 NM radius, centred at 592103N 0025401W <br/>Upper limit: 2000 FT SFC<br/>Lower limit: SFC <br/>Class: </td><td>FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2</td></tr></table> + #rdpStyleMap + + true + true + relativeToGround + + +relativeToGround +-2.90035,59.3841574452,609.6 -2.9070510658,59.3839810493,609.6 -2.9136808917,59.3834537366,609.6 -2.9201690019,59.3825811129,609.6 -2.9264464399,59.3813724543,609.6 -2.9324465072,59.3798406077,609.6 -2.938105477,59.3780018533,609.6 -2.943363275,59.3758757303,609.6 -2.9481641199,59.3734848273,609.6 -2.9524571166,59.3708545414,609.6 -2.9561967958,59.368012806,609.6 -2.9593435949,59.3649897932,609.6 -2.9618642732,59.3618175912,609.6 -2.9637322601,59.3585298629,609.6 -2.9649279298,59.3551614874,609.6 -2.9654388023,59.3517481885,609.6 -2.9652596673,59.3483261563,609.6 -2.9643926307,59.3449316622,609.6 -2.9628470836,59.3416006752,609.6 -2.9606395945,59.338368481,609.6 -2.9577937253,59.3352693088,609.6 -2.9543397752,59.3323359702,609.6 -2.9503144539,59.3295995128,609.6 -2.9457604882,59.3270888933,609.6 -2.9407261668,59.3248306723,609.6 -2.9352648279,59.3228487353,609.6 -2.9294342945,59.3211640419,609.6 -2.9232962652,59.3197944051,609.6 -2.9169156639,59.3187543049,609.6 -2.9103599579,59.3180547361,609.6 -2.9036984496,59.3177030933,609.6 -2.8970015504,59.3177030933,609.6 -2.8903400421,59.3180547361,609.6 -2.8837843361,59.3187543049,609.6 -2.8774037348,59.3197944051,609.6 -2.8712657055,59.3211640419,609.6 -2.8654351721,59.3228487353,609.6 -2.8599738332,59.3248306723,609.6 -2.8549395118,59.3270888933,609.6 -2.8503855461,59.3295995128,609.6 -2.8463602248,59.3323359702,609.6 -2.8429062747,59.3352693088,609.6 -2.8400604055,59.338368481,609.6 -2.8378529164,59.3416006752,609.6 -2.8363073693,59.3449316622,609.6 -2.8354403327,59.3483261563,609.6 -2.8352611977,59.3517481885,609.6 -2.8357720702,59.3551614874,609.6 -2.8369677399,59.3585298629,609.6 -2.8388357268,59.3618175912,609.6 -2.8413564051,59.3649897932,609.6 -2.8445032042,59.368012806,609.6 -2.8482428834,59.3708545414,609.6 -2.8525358801,59.3734848273,609.6 -2.857336725,59.3758757303,609.6 -2.862594523,59.3780018533,609.6 -2.8682534928,59.3798406077,609.6 -2.8742535601,59.3813724543,609.6 -2.8805309981,59.3825811129,609.6 -2.8870191083,59.3834537366,609.6 -2.8936489342,59.3839810493,609.6 -2.90035,59.3841574452,609.6 + + + + + + + + diff --git a/Fences.tsp b/Fences.tsp new file mode 100644 index 0000000000..baea4a733c --- /dev/null +++ b/Fences.tsp @@ -0,0 +1,20615 @@ +NAME: example +TYPE: TSP +DIMENSION: 20609 +EDGE_WEIGHT_TYPE: EUC_2D +NODE_COORD_SECTION +1 50.3216666667 -5.5116666667 +2 50.6416666667 -5.075 +3 50.7166666667 -5.2083333333 +4 50.6583333333 -5.4 +5 50.5333333333 -5.5666666667 +6 50.4 -5.65 +7 50.3216666667 -5.5116666667 +8 50.1669444444 -3.7944444444 +9 49.6219444444 -4.1605555556 +10 49.6847222222 -3.82 +11 50.0608333333 -3.575 +12 50.1669444444 -3.7944444444 +13 50.0608333333 -3.575 +14 49.6847222222 -3.82 +15 49.7813888889 -3.2819444444 +16 50.0175 -3.4861111111 +17 50.0608333333 -3.575 +18 50.0519840728 -5.2317694444 +19 50.0518087079 -5.2382609639 +20 50.0512838469 -5.244706809 +21 50.0504131826 -5.2510616297 +22 50.0492028405 -5.2572807223 +23 50.0476613353 -5.2633203464 +24 50.0457995106 -5.2691380355 +25 50.0436304617 -5.2746928974 +26 50.0411694431 -5.2799459031 +27 50.0384337598 -5.2848601634 +28 50.0354426457 -5.2894011878 +29 50.0322171262 -5.2935371276 +30 50.0287798704 -5.2972389989 +31 50.0251550305 -5.3004808854 +32 50.0213680712 -5.3032401186 +33 50.01744559 -5.3054974349 +34 50.0134151297 -5.3072371079 +35 50.0093049843 -5.308447056 +36 50.0051440001 -5.3091189239 +37 50.0009613725 -5.3092481369 +38 49.9967864416 -5.3088339296 +39 49.9926484858 -5.3078793473 +40 49.9885765165 -5.3063912206 +41 49.9845990758 -5.3043801136 +42 49.9807440358 -5.3018602465 +43 49.9770384047 -5.2988493928 +44 49.9735081377 -5.2953687514 +45 49.9701779565 -5.2914427962 +46 49.9670711763 -5.2870991023 +47 49.9642095444 -5.2823681521 +48 49.9616130881 -5.2772831207 +49 49.9592999758 -5.2718796434 +50 49.957286391 -5.2661955671 +51 49.9555864196 -5.2602706859 +52 49.9542119522 -5.2541464643 +53 49.9531726018 -5.2478657491 +54 49.9524756371 -5.2414724716 +55 49.952125932 -5.2350113432 +56 49.952125932 -5.2285275456 +57 49.9524756371 -5.2220664173 +58 49.9531726018 -5.2156731398 +59 49.9542119522 -5.2093924246 +60 49.9555864196 -5.203268203 +61 49.957286391 -5.1973433218 +62 49.9592999758 -5.1916592454 +63 49.9616130881 -5.1862557682 +64 49.9642095444 -5.1811707367 +65 49.9670711763 -5.1764397866 +66 49.9701779565 -5.1720960927 +67 49.9735081377 -5.1681701375 +68 49.9770384047 -5.1646894961 +69 49.9807440358 -5.1616786423 +70 49.9845990758 -5.1591587753 +71 49.9885765165 -5.1571476683 +72 49.9926484858 -5.1556595416 +73 49.9967864416 -5.1547049593 +74 50.0009613725 -5.154290752 +75 50.0051440001 -5.154419965 +76 50.0093049843 -5.1550918329 +77 50.0134151297 -5.156301781 +78 50.01744559 -5.158041454 +79 50.0213680712 -5.1602987703 +80 50.0251550305 -5.1630580035 +81 50.0287798704 -5.16629989 +82 50.0322171262 -5.1700017613 +83 50.0354426457 -5.1741377011 +84 50.0384337598 -5.1786787255 +85 50.0411694431 -5.1835929857 +86 50.0436304617 -5.1888459915 +87 50.0457995106 -5.1944008533 +88 50.0476613353 -5.2002185425 +89 50.0492028405 -5.2062581666 +90 50.0504131826 -5.2124772592 +91 50.0512838469 -5.2188320799 +92 50.0518087079 -5.225277925 +93 50.0519840728 -5.2317694444 +94 50.0354596389 -5.2893774722 +95 49.9716666667 -5.3783333333 +96 49.8566666667 -5.2 +97 49.94131175 -5.1243299444 +98 49.969289 -5.1732655 +99 49.9662693871 -5.1776868569 +100 49.9634969443 -5.1824813042 +101 49.9609907962 -5.1876157091 +102 49.9587682276 -5.1930546103 +103 49.9568445653 -5.198760463 +104 49.9552330729 -5.2046938963 +105 49.9539448608 -5.2108139835 +106 49.9529888094 -5.2170785222 +107 49.9523715092 -5.2234443235 +108 49.952097215 -5.2298675064 +109 49.9521678175 -5.2363037984 +110 49.9525828301 -5.2427088373 +111 49.9533393922 -5.2490384744 +112 49.9544322888 -5.2552490759 +113 49.9558539861 -5.2612978212 +114 49.9575946829 -5.2671429954 +115 49.9596423778 -5.2727442751 +116 49.9619829511 -5.2780630047 +117 49.9646002613 -5.2830624614 +118 49.9674762558 -5.2877081082 +119 49.9705910944 -5.2919678313 +120 49.9739232851 -5.2958121626 +121 49.9774498319 -5.2992144834 +122 49.9811463922 -5.3021512098 +123 49.9849874443 -5.3046019571 +124 49.9889464626 -5.3065496835 +125 49.9929961005 -5.3079808099 +126 49.9971083784 -5.3088853174 +127 50.0012548768 -5.30925682 +128 50.0054069326 -5.309092612 +129 50.0095358368 -5.3083936908 +130 50.013613033 -5.3071647539 +131 50.0176103157 -5.3054141696 +132 50.0215000252 -5.3031539236 +133 50.0252552394 -5.3003995384 +134 50.0288499612 -5.2971699697 +135 50.0322592989 -5.2934874772 +136 50.0354596389 -5.2893774722 +137 50.2122222222 -4.7830555556 +138 50.1566666667 -4.9083333333 +139 50.0 -4.9083333333 +140 50.1238888889 -4.7077777778 +141 50.2122222222 -4.7830555556 +142 49.9851711667 -5.0849987222 +143 49.9462036944 -4.9428074167 +144 50.0 -4.9083333333 +145 50.1566666667 -4.9083333333 +146 50.0833333333 -4.9966666667 +147 49.9851711667 -5.0849987222 +148 49.9851711667 -5.0849987222 +149 49.8566666667 -5.2 +150 49.8566666667 -5.0 +151 49.9462036944 -4.9428074167 +152 49.9851711667 -5.0849987222 +153 50.3002777778 -4.6119444444 +154 50.2005555556 -4.7730555556 +155 50.1561111111 -4.7352777778 +156 50.2638888889 -4.4161111111 +157 50.3158333333 -4.4605555556 +158 50.3055555556 -4.5311111111 +159 50.3002777778 -4.6119444444 +160 50.2638888889 -4.4161111111 +161 50.1561111111 -4.7352777778 +162 50.1238888889 -4.7077777778 +163 50.2283333333 -4.3858333333 +164 50.2638888889 -4.4161111111 +165 50.2925 -4.7261111111 +166 50.2797222222 -4.7463888889 +167 50.2372222222 -4.7447222222 +168 50.2122222222 -4.7830555556 +169 50.2005555556 -4.7730555556 +170 50.3002777778 -4.6119444444 +171 50.2925 -4.7261111111 +172 49.9483333333 -4.9413888889 +173 49.8566666667 -5.0 +174 49.4625 -5.0 +175 49.6208333333 -4.1675 +176 49.9483333333 -4.9413888889 +177 49.7944444444 -4.575 +178 49.6208333333 -4.1675 +179 49.6219444444 -4.1605555556 +180 49.7438888889 -4.0794444444 +181 49.7944444444 -4.575 +182 50.1944444444 -4.4919444444 +183 50.1238888889 -4.7077777778 +184 50.0 -4.9083333333 +185 49.9483333333 -4.9413888889 +186 49.7944444444 -4.575 +187 49.7438888889 -4.0794444444 +188 50.1063888889 -3.8355555556 +189 50.1003226175 -3.8477298237 +190 50.094429589 -3.8600996985 +191 50.0888258225 -3.8727887629 +192 50.0835184994 -3.8857806495 +193 50.0785144188 -3.8990586201 +194 50.0738199893 -3.9126055863 +195 50.0694412212 -3.926404131 +196 50.0653837191 -3.9404365295 +197 50.061652675 -3.9546847725 +198 50.058252862 -3.9691305873 +199 50.0551886287 -3.9837554609 +200 50.0524638934 -3.9985406625 +201 50.05008214 -4.0134672665 +202 50.0480464131 -4.0285161756 +203 50.0463593148 -4.0436681441 +204 50.0450230012 -4.0589038012 +205 50.04403918 -4.0742036748 +206 50.0434091085 -4.0895482148 +207 50.0431335916 -4.104917817 +208 50.0432129814 -4.120292847 +209 50.0436471765 -4.1356536637 +210 50.0444356221 -4.1509806431 +211 50.0455773107 -4.1662542024 +212 50.0470707833 -4.1814548235 +213 50.0489141315 -4.1965630767 +214 50.0511049992 -4.2115596442 +215 50.0536405859 -4.2264253437 +216 50.05651765 -4.241141152 +217 50.0597325127 -4.2556882278 +218 50.0632810627 -4.2700479348 +219 50.0671587608 -4.2842018648 +220 50.0713606457 -4.2981318601 +221 50.0758813399 -4.311820036 +222 50.0807150566 -4.3252488027 +223 50.0858556064 -4.3384008876 +224 50.0912964049 -4.3512593561 +225 50.097030481 -4.3638076335 +226 50.1030504853 -4.3760295253 +227 50.109348699 -4.387909238 +228 50.1159170439 -4.3994313989 +229 50.1227470915 -4.4105810759 +230 50.1298300744 -4.4213437965 +231 50.1371568961 -4.4317055664 +232 50.1447181433 -4.4416528883 +233 50.1525040966 -4.4511727785 +234 50.1605047435 -4.4602527853 +235 50.1687097899 -4.4688810044 +236 50.1771086739 -4.4770460956 +237 50.1856905783 -4.484737298 +238 50.1944444444 -4.4919444444 +239 50.3177777778 -4.1091666667 +240 50.1944444444 -4.4919444444 +241 50.1856225616 -4.4849292755 +242 50.1770362709 -4.477234108 +243 50.1686330948 -4.4690648117 +244 50.160423856 -4.460432153 +245 50.152419122 -4.4513474783 +246 50.1446291917 -4.4418226976 +247 50.1370640831 -4.4318702695 +248 50.1297335201 -4.421503184 +249 50.1226469211 -4.4107349457 +250 50.1158133869 -4.3995795559 +251 50.1092416896 -4.3880514944 +252 50.1029402616 -4.376165701 +253 50.0969171856 -4.3639375563 +254 50.0911801839 -4.3513828619 +255 50.0857366098 -4.3385178203 +256 50.0805934379 -4.3253590148 +257 50.0757572558 -4.3119233883 +258 50.071234256 -4.2982282225 +259 50.0670302284 -4.2842911159 +260 50.0631505531 -4.2701299621 +261 50.0596001938 -4.2557629282 +262 50.056383692 -4.2412084315 +263 50.0535051612 -4.2264851176 +264 50.0509682819 -4.2116118373 +265 50.0487762975 -4.1966076236 +266 50.0469320097 -4.1814916682 +267 50.0454377758 -4.1662832985 +268 50.0442955053 -4.1510019541 +269 50.0435066578 -4.1356671629 +270 50.0430722415 -4.1202985175 +271 50.0429928112 -4.1049156516 +272 50.0432684685 -4.0895382162 +273 50.0438988612 -4.0741858556 +274 50.0448831838 -4.0588781838 +275 50.0462201785 -4.0436347606 +276 50.0479081368 -4.0284750679 +277 50.0499449013 -4.0134184863 +278 50.0523278689 -3.9984842711 +279 50.0550539932 -3.9836915291 +280 50.0581197887 -3.9690591956 +281 50.0615213351 -3.9546060106 +282 50.0652542816 -3.9403504966 +283 50.0693138528 -3.9263109353 +284 50.0736948539 -3.9125053453 +285 50.0783916776 -3.89895146 +286 50.0833983106 -3.8856667055 +287 50.0887083411 -3.8726681787 +288 50.0943149665 -3.8599726265 +289 50.1002110019 -3.8475964243 +290 50.1063888889 -3.8355555556 +291 50.1669444444 -3.7944444444 +292 50.3177777778 -4.1091666667 +293 50.2283333333 -4.3858333333 +294 50.3177777778 -4.1091666667 +295 50.2930555556 -4.0569444444 +296 50.2962012969 -4.0536641121 +297 50.2995200299 -4.0508306672 +298 50.3029899108 -4.0484794125 +299 50.3065822551 -4.0466298918 +300 50.3102673594 -4.0452975128 +301 50.3140147464 -4.0444934154 +302 50.3177934166 -4.0442243764 +303 50.3215721043 -4.0444927492 +304 50.3253195366 -4.0452964397 +305 50.3290046915 -4.0466289201 +306 50.3325970559 -4.0484792784 +307 50.3360668781 -4.050832305 +308 50.339385415 -4.0536686156 +309 50.3425251708 -4.0569648077 +310 50.3454601258 -4.0606936531 +311 50.3481659531 -4.0648243209 +312 50.3506202208 -4.0693226319 +313 50.3528025791 -4.0741513417 +314 50.3546949305 -4.0792704488 +315 50.3562815802 -4.0846375278 +316 50.3575493674 -4.0902080822 +317 50.3584877753 -4.0959359153 +318 50.3590890188 -4.1017735161 +319 50.3593481099 -4.1076724557 +320 50.3592628989 -4.1135837926 +321 50.3588340927 -4.1194584815 +322 50.3580652491 -4.1252477834 +323 50.3569627465 -4.1309036735 +324 50.3555357309 -4.136379242 +325 50.3537960396 -4.1416290858 +326 50.351758102 -4.1466096878 +327 50.3494388193 -4.1512797789 +328 50.3468574234 -4.1556006814 +329 50.3440353162 -4.1595366302 +330 50.3409958917 -4.163055069 +331 50.3377643405 -4.1661269193 +332 50.3343674403 -4.1687268196 +333 50.3308333333 -4.1708333333 +334 50.2283333333 -4.3858333333 +335 50.7072222222 -4.0294444444 +336 50.6719444444 -4.0613888889 +337 50.6247222222 -4.0169444444 +338 50.6288888889 -3.9669444444 +339 50.6236111111 -3.9533333333 +340 50.6602777778 -3.9369444444 +341 50.7197222222 -3.9816666667 +342 50.7072222222 -4.0294444444 +343 50.6719444444 -4.0613888889 +344 50.6297222222 -4.0994444444 +345 50.5972222222 -4.0788888889 +346 50.6238888889 -4.0266666667 +347 50.6247222222 -4.0169444444 +348 50.6719444444 -4.0613888889 +349 50.6238888889 -4.0266666667 +350 50.5972222222 -4.0788888889 +351 50.5672222222 -4.06 +352 50.5738888889 -3.9755555556 +353 50.6236111111 -3.9533333333 +354 50.6288888889 -3.9669444444 +355 50.6247222222 -4.0169444444 +356 50.6238888889 -4.0266666667 +357 50.7055555556 -2.75 +358 50.7069818889 -2.7539289167 +359 50.7115620278 -2.7687341389 +360 50.7163986111 -2.7852465278 +361 50.717073 -2.7919162222 +362 50.7168574444 -2.7971543056 +363 50.7180863333 -2.8015669444 +364 50.71687425 -2.8077796667 +365 50.7178408333 -2.8110547222 +366 50.7203182778 -2.8169062778 +367 50.7229190278 -2.8306950556 +368 50.7219649722 -2.8383291111 +369 50.7232648056 -2.8451533056 +370 50.7273595556 -2.8632228333 +371 50.7303860278 -2.8797339722 +372 50.732233 -2.8967570833 +373 50.7329700278 -2.9061245 +374 50.731285 -2.9145946944 +375 50.7280638889 -2.9238843611 +376 50.7239981389 -2.9262131111 +377 50.7231707778 -2.9284638056 +378 50.7226041111 -2.9318530833 +379 50.7211471667 -2.9340910833 +380 50.7197072222 -2.9342041389 +381 50.7189730556 -2.9360313333 +382 50.7178311389 -2.9438005278 +383 50.7128335 -2.9500746944 +384 50.7123653889 -2.9523317222 +385 50.7119313056 -2.9613887778 +386 50.7121893889 -2.9628106111 +387 50.7096457222 -2.96587475 +388 50.7072464444 -2.9731907222 +389 50.7046847222 -2.9783781111 +390 50.7045447222 -2.9843237222 +391 50.7055051389 -2.9877430833 +392 50.7054859167 -2.9900088333 +393 50.7041956667 -2.9936640833 +394 50.7015418889 -2.9989896667 +395 50.6997871111 -3.0043338611 +396 50.6994916667 -3.0073015 +397 50.6984485278 -3.0135101667 +398 50.6980369722 -3.0194490278 +399 50.6985280833 -3.0249826389 +400 50.6993149722 -3.0275488889 +401 50.6998780278 -3.0350669722 +402 50.7014981389 -3.0450162778 +403 50.7016410833 -3.0491265556 +404 50.7015103056 -3.0536555833 +405 50.7020716944 -3.0611743056 +406 50.7019391389 -3.0658449167 +407 50.7014271944 -3.07263125 +408 50.7013163889 -3.0748946944 +409 50.7004809444 -3.077708 +410 50.7002801389 -3.0799693056 +411 50.6983760556 -3.0816249444 +412 50.6956520833 -3.0843944167 +413 50.6948971111 -3.0882003056 +414 50.6924599722 -3.0891350833 +415 50.6908413889 -3.0890976111 +416 50.68713475 -3.0911355 +417 50.68433925 -3.0919200833 +418 50.6845798056 -3.0950402778 +419 50.685 -3.0955555556 +420 50.6138888889 -3.25 +421 50.5 -3.2916666667 +422 50.5666666667 -3.0833333333 +423 50.5666666667 -2.9722222222 +424 50.5666666667 -2.8611111111 +425 50.5666666667 -2.75 +426 50.7055555556 -2.75 +427 50.5666666667 -2.75 +428 50.5666666667 -3.0833333333 +429 50.5 -3.2916666667 +430 50.4166666667 -3.2916666667 +431 50.1333333333 -3.075 +432 50.0333333333 -2.9666666667 +433 50.0333333333 -2.75 +434 50.5666666667 -2.75 +435 50.6383333333 -2.5733333333 +436 50.6166666667 -2.6916666667 +437 50.5666666667 -2.7 +438 50.5666666667 -2.75 +439 50.4919444444 -2.5 +440 50.5666666667 -2.5 +441 50.5666666667 -2.5233333333 +442 50.5916666667 -2.4966666667 +443 50.6266666667 -2.5416666667 +444 50.6383333333 -2.5733333333 +445 50.7278279975 -2.24 +446 50.7276613075 -2.2419105304 +447 50.7271736038 -2.2436793273 +448 50.726401066 -2.2451751801 +449 50.7254010021 -2.24628714 +450 50.724247594 -2.2469327516 +451 50.7230263925 -2.2470641634 +452 50.7218279703 -2.2466716685 +453 50.7207412039 -2.2457844129 +454 50.7198466836 -2.2444682231 +455 50.7192107394 -2.2428207176 +456 50.7188805253 -2.240964066 +457 50.7188805253 -2.239035934 +458 50.7192107394 -2.2371792824 +459 50.7198466836 -2.2355317769 +460 50.7207412039 -2.2342155871 +461 50.7218279703 -2.2333283315 +462 50.7230263925 -2.2329358366 +463 50.724247594 -2.2330672484 +464 50.7254010021 -2.23371286 +465 50.726401066 -2.2348248199 +466 50.7271736038 -2.2363206727 +467 50.7276613075 -2.2380894696 +468 50.7278279975 -2.24 +469 50.5666666667 -2.75 +470 50.0333333333 -2.75 +471 50.0333333333 -2.5 +472 50.4919444444 -2.5 +473 50.5666666667 -2.75 +474 50.5833333333 -2.3333333333 +475 50.5 -2.3333333333 +476 50.5 -2.5 +477 50.4919444444 -2.5 +478 50.4166666667 -2.25 +479 50.4883333333 -2.2883333333 +480 50.5 -2.2833333333 +481 50.5316666667 -2.2733333333 +482 50.5833333333 -2.2705555556 +483 50.5833333333 -2.3333333333 +484 50.4919444444 -2.5 +485 50.0333333333 -2.5 +486 50.0333333333 -2.25 +487 50.4166666667 -2.25 +488 50.4919444444 -2.5 +489 50.6722222222 -2.1319444444 +490 50.6744444444 -2.1936111111 +491 50.6402777778 -2.1936111111 +492 50.6333333333 -2.2416666667 +493 50.6166666667 -2.2463888889 +494 50.5933333333 -2.27 +495 50.5316666667 -2.2733333333 +496 50.5 -2.2833333333 +497 50.4883333333 -2.2883333333 +498 50.4166666667 -2.25 +499 50.4166666667 -2.145 +500 50.4483333333 -2.0416666667 +501 50.5083333333 -2.0119444444 +502 50.5841666667 -2.0777777778 +503 50.6122222222 -2.1369444444 +504 50.6308333333 -2.1313888889 +505 50.6638888889 -2.1255555556 +506 50.6722222222 -2.1319444444 +507 50.6072222222 -1.9430555556 +508 50.60445 -1.9470027778 +509 50.6030111111 -1.9484166667 +510 50.5973472222 -1.9506833333 +511 50.5944666667 -1.9489916667 +512 50.5921305556 -1.9540805556 +513 50.5911416667 -1.9552111111 +514 50.5903333333 -1.9583222222 +515 50.5907861111 -1.9653861111 +516 50.5904277778 -1.9679277778 +517 50.5907861111 -1.9701888889 +518 50.5901583333 -1.9738611111 +519 50.5899805556 -1.9772527778 +520 50.5894416667 -1.9812083333 +521 50.5900694444 -1.9857305556 +522 50.5896222222 -1.9877083333 +523 50.5903416667 -1.9964666667 +524 50.5899805556 -2.0029666667 +525 50.5895305556 -2.0086194444 +526 50.5888111111 -2.014975 +527 50.5880916667 -2.0185083333 +528 50.5871916667 -2.0244416667 +529 50.5851222222 -2.0279722222 +530 50.5829611111 -2.0306527778 +531 50.5798138889 -2.0361611111 +532 50.5784638889 -2.0394083333 +533 50.5772027778 -2.0427972222 +534 50.5765722222 -2.0454805556 +535 50.5761194444 -2.049575 +536 50.5754 -2.0524 +537 50.5763888889 -2.0555555556 +538 50.57 -2.0655555556 +539 50.5083333333 -2.0119444444 +540 50.5 -2.0161111111 +541 50.5 -1.9430555556 +542 50.6072222222 -1.9430555556 +543 50.4908333333 -1.2022222222 +544 50.1055555556 -1.7019444444 +545 50.0 -1.7169444444 +546 50.0 -1.1905555556 +547 50.4908333333 -1.2022222222 +548 50.6166666667 -1.0363888889 +549 50.5 -1.19 +550 50.5 -0.5369444444 +551 50.6166666667 -0.6605555556 +552 50.6166666667 -1.0363888889 +553 50.5 -1.19 +554 50.4908333333 -1.2022222222 +555 50.0 -1.1905555556 +556 50.0 -0.8333333333 +557 50.5 -0.8333333333 +558 50.5 -1.19 +559 50.5 -0.8333333333 +560 50.0 -0.8333333333 +561 50.0 -0.5333333333 +562 50.4966666667 -0.5333333333 +563 50.5 -0.5369444444 +564 50.5 -0.8333333333 +565 50.4966666667 -0.5333333333 +566 50.0 -0.5333333333 +567 50.0 -0.5319444444 +568 50.2297222222 -0.2530555556 +569 50.4966666667 -0.5333333333 +570 50.9236111111 0.9261111111 +571 50.9472222222 0.8966666667 +572 50.9316666667 0.8358333333 +573 50.9055555556 0.7966666667 +574 50.8769444444 0.8375 +575 50.8772222222 0.8997222222 +576 50.8911111111 0.9369444444 +577 50.9236111111 0.9261111111 +578 50.6886019548 -3.3475 +579 50.6884315287 -3.3501377665 +580 50.6879272312 -3.3526674871 +581 50.6871097185 -3.3549855484 +582 50.6860124748 -3.3569970187 +583 50.684680439 -3.3586195398 +584 50.683168162 -3.3597866995 +585 50.6815375708 -3.3604507489 +586 50.6798554304 -3.3605845512 +587 50.6781906099 -3.3601826846 +588 50.6766112617 -3.3592616556 +589 50.675182033 -3.3578592141 +590 50.6739614205 -3.356032801 +591 50.6729993786 -3.3538571928 +592 50.6723352766 -3.3514214394 +593 50.67199629 -3.348825222 +594 50.67199629 -3.346174778 +595 50.6723352766 -3.3435785606 +596 50.6729993786 -3.3411428072 +597 50.6739614205 -3.338967199 +598 50.675182033 -3.3371407859 +599 50.6766112617 -3.3357383444 +600 50.6781906099 -3.3348173154 +601 50.6798554304 -3.3344154488 +602 50.6815375708 -3.3345492511 +603 50.683168162 -3.3352133005 +604 50.684680439 -3.3363804602 +605 50.6860124748 -3.3380029813 +606 50.6871097185 -3.3400144516 +607 50.6879272312 -3.3423325129 +608 50.6884315287 -3.3448622335 +609 50.6886019548 -3.3475 +610 51.3376777778 -7.1874361111 +611 50.9625111111 -7.8681916667 +612 50.7846722222 -7.8686888889 +613 50.6354777778 -7.820425 +614 50.4391444444 -7.6007361111 +615 50.2977472222 -7.0891277778 +616 50.4771666667 -6.0128138889 +617 51.2711527778 -6.2787027778 +618 51.3376777778 -7.1874361111 +619 51.2711527778 -6.2787027778 +620 50.4771666667 -6.0128138889 +621 50.5032416667 -5.7262777778 +622 51.1065583333 -5.4195055556 +623 51.2020805556 -5.4255305556 +624 51.2711527778 -6.2787027778 +625 51.2020805556 -5.4255305556 +626 51.1065583333 -5.4195055556 +627 50.5032416667 -5.7262777778 +628 50.7243333333 -4.6557722222 +629 50.7396694444 -4.6538055556 +630 50.7866166667 -4.5574972222 +631 50.9120277778 -4.5643666667 +632 51.1745361111 -5.1057833333 +633 51.2020805556 -5.4255305556 +634 51.1005694444 -4.2580305556 +635 51.0870916667 -4.2573722222 +636 51.0876416667 -4.2288388889 +637 51.0828472222 -4.2207555556 +638 51.0832388889 -4.2000694444 +639 51.1016611111 -4.2009444444 +640 51.1005694444 -4.2580305556 +641 51.6602777778 -5.3083333333 +642 51.6027777778 -5.4022222222 +643 51.5933780264 -5.3963665818 +644 51.5840734082 -5.3901403276 +645 51.5749035623 -5.3834198158 +646 51.5658786995 -5.3762128249 +647 51.5570088636 -5.3685276609 +648 51.5483039199 -5.3603731468 +649 51.539773545 -5.351758612 +650 51.5314272159 -5.342693881 +651 51.5232742004 -5.3331892616 +652 51.5153235465 -5.3232555331 +653 51.5075840732 -5.3129039336 +654 51.5000643609 -5.3021461467 +655 51.4927727422 -5.2909942889 +656 51.4857172931 -5.2794608951 +657 51.4789058244 -5.2675589047 +658 51.4723458735 -5.2553016477 +659 51.4660446964 -5.2427028289 +660 51.4600092598 -5.2297765136 +661 51.454246234 -5.216537112 +662 51.448761986 -5.2029993633 +663 51.4435625724 -5.1891783197 +664 51.4386537333 -5.1750893305 +665 51.4340408864 -5.1607480254 +666 51.4297291211 -5.1461702976 +667 51.4257231931 -5.1313722874 +668 51.4220275198 -5.1163703645 +669 51.4186461753 -5.1011811112 +670 51.4155828866 -5.0858213045 +671 51.4128410291 -5.070307899 +672 51.4104236237 -5.0546580086 +673 51.4083333333 -5.0388888889 +674 51.4833333333 -4.9088888889 +675 51.4833333333 -4.9836111111 +676 51.4833333333 -5.0583333333 +677 51.525 -5.0916666667 +678 51.6516666667 -5.0555555556 +679 51.6602777778 -5.0786111111 +680 51.6602777778 -5.1934722222 +681 51.6602777778 -5.3083333333 +682 51.6516666667 -5.0555555556 +683 51.525 -5.0916666667 +684 51.4833333333 -5.0583333333 +685 51.4833333333 -4.9088888889 +686 51.5416666667 -4.8083333333 +687 51.605 -4.8922222222 +688 51.605 -4.9222222222 +689 51.6100303992 -4.9279167223 +690 51.614754824 -4.9342578797 +691 51.6192510473 -4.9410141992 +692 51.62350497 -4.9481646133 +693 51.6275032486 -4.9556867999 +694 51.6312333384 -4.9635572517 +695 51.634683533 -4.9717513502 +696 51.6378430019 -4.9802434429 +697 51.6407018251 -4.9890069249 +698 51.6432510247 -4.9980143228 +699 51.6454825939 -5.0072373821 +700 51.6473895223 -5.0166471575 +701 51.6489658186 -5.0262141049 +702 51.6502065296 -5.0359081761 +703 51.6511077564 -5.0456989152 +704 51.6516666667 -5.0555555556 +705 51.6375 -4.8366666667 +706 51.6375 -4.73 +707 51.6408567001 -4.7302715604 +708 51.6441790898 -4.7310874734 +709 51.6474330816 -4.7324394857 +710 51.6505852827 -4.734313836 +711 51.6536033378 -4.7366913916 +712 51.6564562626 -4.7395478412 +713 51.6591147623 -4.7428539406 +714 51.6615515337 -4.746575811 +715 51.6637415465 -4.7506752849 +716 51.6656623018 -4.7551102976 +717 51.6672940641 -4.7598353191 +718 51.6686200655 -4.7648018228 +719 51.6696266787 -4.7699587861 +720 51.6703035578 -4.7752532169 +721 51.6706437457 -4.7806307011 +722 51.6706437457 -4.7860359656 +723 51.6703035578 -4.7914134498 +724 51.6696266787 -4.7967078805 +725 51.6686200655 -4.8018648438 +726 51.6672940641 -4.8068313476 +727 51.6656623018 -4.811556369 +728 51.6637415465 -4.8159913818 +729 51.6615515337 -4.8200908557 +730 51.6591147623 -4.8238127261 +731 51.6564562626 -4.8271188255 +732 51.6536033378 -4.829975275 +733 51.6505852827 -4.8323528307 +734 51.6474330816 -4.834227181 +735 51.6441790898 -4.8355791933 +736 51.6408567001 -4.8363951063 +737 51.6375 -4.8366666667 +738 51.6375 -4.8366666667 +739 51.5355555556 -5.0383333333 +740 51.5288043613 -5.0309417218 +741 51.5222339864 -5.0231463892 +742 51.515879783 -5.0149045172 +743 51.509753581 -5.0062316321 +744 51.5038667816 -4.9971440429 +745 51.4982303358 -4.9876588105 +746 51.4928547252 -4.9777937157 +747 51.4877499426 -4.9675672259 +748 51.4829254744 -4.9569984611 +749 51.478390283 -4.946107158 +750 51.4741527909 -4.934913634 +751 51.4702208656 -4.9234387502 +752 51.4666018052 -4.9117038729 +753 51.4633023255 -4.8997308346 +754 51.460328548 -4.8875418953 +755 51.4576859887 -4.8751597012 +756 51.4553795484 -4.8626072445 +757 51.4534135038 -4.849907822 +758 51.4517915 -4.8370849928 +759 51.4505165438 -4.8241625367 +760 51.4495909985 -4.8111644114 +761 51.4490165796 -4.7981147096 +762 51.4487943517 -4.785037616 +763 51.4489247268 -4.7719573642 +764 51.449407463 -4.7588981934 +765 51.4502416659 -4.7458843053 +766 51.4514257891 -4.7329398206 +767 51.4529576379 -4.7200887363 +768 51.4548343726 -4.7073548826 +769 51.4570525138 -4.6947618804 +770 51.4596079487 -4.6823330987 +771 51.4624959382 -4.6700916132 +772 51.4657111258 -4.6580601642 +773 51.4692475467 -4.646261116 +774 51.4730986389 -4.6347164165 +775 51.4772572546 -4.6234475573 +776 51.4817156735 -4.6124755347 +777 51.4864656162 -4.6018208114 +778 51.4914982594 -4.5915032789 +779 51.4968042517 -4.5815422215 +780 51.5023737305 -4.5719562797 +781 51.5081963399 -4.5627634166 +782 51.514261249 -4.5539808837 +783 51.5205571722 -4.5456251891 +784 51.5270723892 -4.5377120657 +785 51.5337947665 -4.5302564419 +786 51.5407117792 -4.5232724124 +787 51.5478105344 -4.5167732117 +788 51.5550777941 -4.5107711877 +789 51.5625 -4.5052777778 +790 51.6375 -4.73 +791 51.6375 -4.8366666667 +792 51.5861111111 -4.4 +793 51.7458333333 -4.4 +794 51.7566666667 -4.4213888889 +795 51.7541666667 -4.55 +796 51.6661111111 -4.6286111111 +797 51.6080555556 -4.6311111111 +798 51.5861111111 -4.4 +799 51.7736111111 -4.4 +800 51.6669444444 -4.4 +801 51.6652909723 -4.3932089918 +802 51.6639604701 -4.386237853 +803 51.6629707362 -4.3791217654 +804 51.6623277443 -4.3719036854 +805 51.6620353749 -4.3646271782 +806 51.6620953927 -4.3573361576 +807 51.6625074354 -4.3500746236 +808 51.6632690162 -4.3428864007 +809 51.6643755387 -4.3358148759 +810 51.6658203243 -4.3289027398 +811 51.6675946518 -4.3221917315 +812 51.6696878099 -4.3157223893 +813 51.6720871608 -4.3095338075 +814 51.674778216 -4.3036634025 +815 51.6777447228 -4.2981466874 +816 51.6809687617 -4.2930170582 +817 51.6844308533 -4.2883055923 +818 51.6881100757 -4.2840408602 +819 51.6919841894 -4.2802487514 +820 51.6960297713 -4.2769523168 +821 51.700222355 -4.2741716265 +822 51.7045365786 -4.2719236467 +823 51.7089463366 -4.2702221333 +824 51.7134249384 -4.2690775454 +825 51.7179452683 -4.2684969787 +826 51.7224799502 -4.268484118 +827 51.7270015129 -4.2690392114 +828 51.7314825564 -4.2701590641 +829 51.7358959184 -4.2718370543 +830 51.7402148389 -4.274063169 +831 51.7444131231 -4.2768240608 +832 51.7484653009 -4.2801031259 +833 51.7523467816 -4.2838806013 +834 51.7560340046 -4.2881336823 +835 51.7595045827 -4.2928366585 +836 51.762737439 -4.2979610682 +837 51.7657129363 -4.3034758704 +838 51.7684129966 -4.3093476325 +839 51.7708212126 -4.3155407334 +840 51.7729229477 -4.3220175804 +841 51.7747054264 -4.328738839 +842 51.7761578122 -4.3356636736 +843 51.7772712745 -4.3427499972 +844 51.778039043 -4.3499547303 +845 51.7784564488 -4.3572340651 +846 51.7785209536 -4.364543735 +847 51.7782321652 -4.3718392867 +848 51.7775918398 -4.3790763538 +849 51.7766038711 -4.3862109299 +850 51.7752742668 -4.3931996384 +851 51.7736111111 -4.4 +852 51.2732537142 -3.2313888889 +853 51.2730758236 -3.2391376971 +854 51.2725431051 -3.2468449835 +855 51.2716584129 -3.2544694515 +856 51.2704264874 -3.2619702543 +857 51.2688539286 -3.2693072156 +858 51.266949161 -3.2764410482 +859 51.2647223876 -3.2833335658 +860 51.2621855343 -3.2899478902 +861 51.2593521862 -3.2962486495 +862 51.2562375131 -3.3022021691 +863 51.2528581878 -3.3077766525 +864 51.2492322963 -3.3129423514 +865 51.2453792395 -3.3176717247 +866 51.241319629 -3.321939585 +867 51.2370751757 -3.3257232319 +868 51.2326685731 -3.3290025716 +869 51.2281233748 -3.3317602224 +870 51.2234638686 -3.3339816043 +871 51.2187149454 -3.3356550146 +872 51.2139019661 -3.336771687 +873 51.209050626 -3.3373258345 +874 51.2041868169 -3.337314677 +875 51.1993364891 -3.3367384523 +876 51.1945255131 -3.3356004111 +877 51.1897795412 -3.3339067956 +878 51.1851238715 -3.331666803 +879 51.1805833133 -3.3288925326 +880 51.1761820552 -3.3255989185 +881 51.1719435371 -3.3218036468 +882 51.1678903259 -3.3175270589 +883 51.1640439963 -3.3127920413 +884 51.1604250162 -3.3076239017 +885 51.1570526395 -3.3020502333 +886 51.1539448039 -3.2961007668 +887 51.1511180366 -3.2898072125 +888 51.1485873672 -3.2832030916 +889 51.1463662487 -3.2763235581 +890 51.1444664867 -3.2692052139 +891 51.1428981776 -3.2618859148 +892 51.1416696551 -3.254404572 +893 51.1407874469 -3.2468009466 +894 51.1402562401 -3.2391154415 +895 51.1400788571 -3.2313888889 +896 51.1402562401 -3.2236623363 +897 51.1407874469 -3.2159768312 +898 51.1416696551 -3.2083732058 +899 51.1428981776 -3.2008918629 +900 51.1444664867 -3.1935725639 +901 51.1463662487 -3.1864542197 +902 51.1485873672 -3.1795746862 +903 51.1511180366 -3.1729705652 +904 51.1539448039 -3.166677011 +905 51.1570526395 -3.1607275445 +906 51.1604250162 -3.155153876 +907 51.1640439963 -3.1499857365 +908 51.1678903259 -3.1452507189 +909 51.1719435371 -3.140974131 +910 51.1761820552 -3.1371788593 +911 51.1805833133 -3.1338852452 +912 51.1851238715 -3.1311109748 +913 51.1897795412 -3.1288709822 +914 51.1945255131 -3.1271773667 +915 51.1993364891 -3.1260393255 +916 51.2041868169 -3.1254631008 +917 51.209050626 -3.1254519433 +918 51.2139019661 -3.1260060908 +919 51.2187149454 -3.1271227631 +920 51.2234638686 -3.1287961735 +921 51.2281233748 -3.1310175554 +922 51.2326685731 -3.1337752061 +923 51.2370751757 -3.1370545459 +924 51.241319629 -3.1408381928 +925 51.2453792395 -3.145106053 +926 51.2492322963 -3.1498354263 +927 51.2528581878 -3.1550011252 +928 51.2562375131 -3.1605756087 +929 51.2593521862 -3.1665291283 +930 51.2621855343 -3.1728298876 +931 51.2647223876 -3.1794442119 +932 51.266949161 -3.1863367296 +933 51.2688539286 -3.1934705622 +934 51.2704264874 -3.2008075235 +935 51.2716584129 -3.2083083262 +936 51.2725431051 -3.2159327943 +937 51.2730758236 -3.2236400807 +938 51.2732537142 -3.2313888889 +939 51.1811111111 -1.8005555556 +940 51.1781799843 -1.804205638 +941 51.1751003506 -1.807520014 +942 51.1718469736 -1.810383437 +943 51.1684458589 -1.8127731156 +944 51.1649241872 -1.8146700582 +945 51.1613100965 -1.8160592224 +946 51.1576324567 -1.8169296313 +947 51.1539206381 -1.8172744577 +948 51.1502042775 -1.817091075 +949 51.1465130403 -1.8163810737 +950 51.1428763847 -1.815150245 +951 51.1393233266 -1.8134085306 +952 51.1358822079 -1.8111699394 +953 51.1325804719 -1.8084524327 +954 51.1294444444 -1.8052777778 +955 51.1127777778 -1.7358333333 +956 51.125 -1.7133333333 +957 51.1336111111 -1.7133333333 +958 51.1455555556 -1.6861111111 +959 51.1491417891 -1.6853632646 +960 51.1527499945 -1.6850302822 +961 51.1563627495 -1.6851969823 +962 51.1599527323 -1.6858622209 +963 51.1634927871 -1.6870210811 +964 51.1669561299 -1.6886649068 +965 51.1703165508 -1.6907813654 +966 51.1735486135 -1.6933545375 +967 51.1766278481 -1.6963650348 +968 51.1795309369 -1.6997901449 +969 51.182235892 -1.7036040013 +970 51.1847222222 -1.7077777778 +971 51.1788888889 -1.7188888889 +972 51.1830555556 -1.7780555556 +973 51.1811111111 -1.8005555556 +974 51.2247222222 -2.1969444444 +975 51.0222222222 -2.1969444444 +976 50.9938888889 -2.1205555556 +977 51.0236111111 -1.9505555556 +978 51.1683333333 -1.9505555556 +979 51.185 -2.1202777778 +980 51.2247222222 -2.1969444444 +981 51.1830555556 -1.7780555556 +982 51.1683333333 -1.9505555556 +983 51.0236111111 -1.9505555556 +984 51.0658333333 -1.7083333333 +985 51.1788888889 -1.7188888889 +986 51.1830555556 -1.7780555556 +987 51.2263888889 -1.6236111111 +988 51.2130555556 -1.6330555556 +989 51.2091666667 -1.6616666667 +990 51.1788888889 -1.7188888889 +991 51.0658333333 -1.7083333333 +992 51.0908333333 -1.5616666667 +993 51.21 -1.5122222222 +994 51.2263888889 -1.6236111111 +995 51.29 -2.0186111111 +996 51.2847222222 -2.0533333333 +997 51.2544444444 -2.1608333333 +998 51.2247222222 -2.1969444444 +999 51.185 -2.1202777778 +1000 51.1683333333 -1.9505555556 +1001 51.1730555556 -1.8902777778 +1002 51.23 -1.9513888889 +1003 51.2275 -1.9627777778 +1004 51.29 -2.0186111111 +1005 51.282470014 -1.97 +1006 51.2822946576 -1.9747091708 +1007 51.2817710539 -1.9793521288 +1008 51.2809065647 -1.9838635968 +1009 51.2797133442 -1.988180155 +1010 51.2782081673 -1.992241136 +1011 51.2764121923 -1.995989481 +1012 51.2743506631 -1.9993725434 +1013 51.2720525523 -2.0023428293 +1014 51.2695501529 -2.0048586647 +1015 51.266878623 -2.0068847788 +1016 51.264075491 -2.008392797 +1017 51.2611801269 -2.009361635 +1018 51.2582331885 -2.0097777904 +1019 51.2552760504 -2.0096355267 +1020 51.2523502221 -2.0089369474 +1021 51.2494967662 -2.0076919612 +1022 51.246755722 -2.005918137 +1023 51.2441655445 -2.0036404518 +1024 51.2417625661 -2.0008909363 +1025 51.2395804878 -1.9977082216 +1026 51.237649908 -1.9941369955 +1027 51.235997895 -1.9902273742 +1028 51.2346476088 -1.9860342001 +1029 51.2336179772 -1.9816162739 +1030 51.2329234326 -1.9770355326 +1031 51.2325737095 -1.972356185 +1032 51.2325737095 -1.967643815 +1033 51.2329234326 -1.9629644674 +1034 51.2336179772 -1.9583837261 +1035 51.2346476088 -1.9539657999 +1036 51.235997895 -1.9497726258 +1037 51.237649908 -1.9458630045 +1038 51.2395804878 -1.9422917784 +1039 51.2417625661 -1.9391090637 +1040 51.2441655445 -1.9363595482 +1041 51.246755722 -1.934081863 +1042 51.2494967662 -1.9323080388 +1043 51.2523502221 -1.9310630526 +1044 51.2552760504 -1.9303644733 +1045 51.2582331885 -1.9302222096 +1046 51.2611801269 -1.930638365 +1047 51.264075491 -1.931607203 +1048 51.266878623 -1.9331152212 +1049 51.2695501529 -1.9351413353 +1050 51.2720525523 -1.9376571707 +1051 51.2743506631 -1.9406274566 +1052 51.2764121923 -1.944010519 +1053 51.2782081673 -1.947758864 +1054 51.2797133442 -1.951819845 +1055 51.2809065647 -1.9561364032 +1056 51.2817710539 -1.9606478712 +1057 51.2822946576 -1.9652908292 +1058 51.282470014 -1.97 +1059 51.3077777778 -1.8344444444 +1060 51.3019444444 -1.9430555556 +1061 51.29 -2.0186111111 +1062 51.2275 -1.9627777778 +1063 51.23 -1.9513888889 +1064 51.1730555556 -1.8902777778 +1065 51.1830555556 -1.7780555556 +1066 51.3077777778 -1.8344444444 +1067 51.2725 -1.6294444444 +1068 51.2316666667 -1.7069444444 +1069 51.2334964065 -1.715059155 +1070 51.2348000136 -1.7234325199 +1071 51.2357586607 -1.7319235049 +1072 51.2363682739 -1.7404960327 +1073 51.2366262626 -1.7491136738 +1074 51.2365315304 -1.757739804 +1075 51.2360844798 -1.7663377624 +1076 51.2352870108 -1.7748710099 +1077 51.2341425123 -1.7833032865 +1078 51.2326558475 -1.7915987684 +1079 51.2308333333 -1.7997222222 +1080 51.1830555556 -1.7780555556 +1081 51.1788888889 -1.7188888889 +1082 51.2091666667 -1.6616666667 +1083 51.2130555556 -1.6330555556 +1084 51.2569444444 -1.6016666667 +1085 51.2725 -1.6294444444 +1086 51.0977777778 -1.7208333333 +1087 51.1175 -1.6452777778 +1088 51.1311111111 -1.6138888889 +1089 51.17 -1.6305555556 +1090 51.1336111111 -1.7133333333 +1091 51.125 -1.7133333333 +1092 51.1088888889 -1.7430555556 +1093 51.0977777778 -1.7208333333 +1094 51.3144444444 -1.7041666667 +1095 51.3077777778 -1.8344444444 +1096 51.2308333333 -1.7997222222 +1097 51.2324672241 -1.7915023174 +1098 51.2339503473 -1.7832265947 +1099 51.2350921193 -1.774814405 +1100 51.2358876884 -1.7663014863 +1101 51.2363336739 -1.7577240116 +1102 51.2364281804 -1.7491184326 +1103 51.2361708064 -1.7405213223 +1104 51.2355626455 -1.7319692174 +1105 51.2346062823 -1.7234984599 +1106 51.2333057807 -1.7151450407 +1107 51.2316666667 -1.7069444444 +1108 51.2725 -1.6294444444 +1109 51.3144444444 -1.7041666667 +1110 51.9127342248 -1.2222222222 +1111 51.9125576553 -1.2277568724 +1112 51.9120298224 -1.2332327248 +1113 51.9111563334 -1.2385916105 +1114 51.9099464672 -1.2437766112 +1115 51.908413075 -1.2487326672 +1116 51.9065724429 -1.2534071653 +1117 51.9044441182 -1.2577504999 +1118 51.9020507004 -1.2617166009 +1119 51.8994176001 -1.2652634235 +1120 51.8965727679 -1.268353394 +1121 51.8935463967 -1.270953807 +1122 51.8903705996 -1.2730371699 +1123 51.8870790687 -1.2745814917 +1124 51.8837067162 -1.2755705115 +1125 51.8802893039 -1.2759938668 +1126 51.8768630632 -1.2758471977 +1127 51.8734643111 -1.2751321884 +1128 51.870129065 -1.2738565432 +1129 51.8668926615 -1.2720338997 +1130 51.8637893825 -1.2696836797 +1131 51.8608520931 -1.2668308788 +1132 51.8581118942 -1.2635057979 +1133 51.8555977944 -1.2597437196 +1134 51.8533364043 -1.2555845326 +1135 51.8513516557 -1.2510723085 +1136 51.84966455 -1.2462548354 +1137 51.8482929371 -1.2411831132 +1138 51.8472513271 -1.2359108155 +1139 51.8465507384 -1.2304937247 +1140 51.8461985817 -1.2249891449 +1141 51.8461985817 -1.2194552996 +1142 51.8465507384 -1.2139507197 +1143 51.8472513271 -1.2085336289 +1144 51.8482929371 -1.2032613312 +1145 51.84966455 -1.198189609 +1146 51.8513516557 -1.193372136 +1147 51.8533364043 -1.1888599119 +1148 51.8555977944 -1.1847007249 +1149 51.8581118942 -1.1809386465 +1150 51.8608520931 -1.1776135656 +1151 51.8637893825 -1.1747607647 +1152 51.8668926615 -1.1724105447 +1153 51.870129065 -1.1705879013 +1154 51.8734643111 -1.169312256 +1155 51.8768630632 -1.1685972467 +1156 51.8802893039 -1.1684505777 +1157 51.8837067162 -1.1688739329 +1158 51.8870790687 -1.1698629527 +1159 51.8903705996 -1.1714072745 +1160 51.8935463967 -1.1734906375 +1161 51.8965727679 -1.1760910505 +1162 51.8994176001 -1.179181021 +1163 51.9020507004 -1.1827278436 +1164 51.9044441182 -1.1866939445 +1165 51.9065724429 -1.1910372791 +1166 51.908413075 -1.1957117772 +1167 51.9099464672 -1.2006678332 +1168 51.9111563334 -1.2058528339 +1169 51.9120298224 -1.2112117197 +1170 51.9125576553 -1.2166875721 +1171 51.9127342248 -1.2222222222 +1172 51.0997222222 -0.8702777778 +1173 51.0738888889 -0.8836111111 +1174 51.0794444444 -0.8277777778 +1175 51.0947222222 -0.8272222222 +1176 51.0997222222 -0.8702777778 +1177 51.2958333333 -0.6655555556 +1178 51.2922222222 -0.6877777778 +1179 51.2772222222 -0.7163888889 +1180 51.2683333333 -0.7191666667 +1181 51.2566666667 -0.7166666667 +1182 51.2633333333 -0.6761111111 +1183 51.2730555556 -0.6616666667 +1184 51.2958333333 -0.6655555556 +1185 51.3227777778 -0.6519444444 +1186 51.3083333333 -0.6883333333 +1187 51.3041666667 -0.6841666667 +1188 51.3044444444 -0.6744444444 +1189 51.3077777778 -0.6641666667 +1190 51.3208333333 -0.6494444444 +1191 51.3227777778 -0.6519444444 +1192 51.3444444444 -0.6747222222 +1193 51.3386111111 -0.6994444444 +1194 51.3208333333 -0.6961111111 +1195 51.3083333333 -0.6883333333 +1196 51.3227777778 -0.6519444444 +1197 51.3427777778 -0.6658333333 +1198 51.3444444444 -0.6747222222 +1199 51.5380555556 0.8011111111 +1200 51.5083333333 0.7833333333 +1201 51.5047222222 0.8511111111 +1202 51.5380555556 0.8011111111 +1203 51.6666666667 1.0666666667 +1204 51.6205555556 0.9266666667 +1205 51.6205555556 1.2008333333 +1206 51.6666666667 1.2702777778 +1207 51.6666666667 1.0666666667 +1208 51.7 1.19 +1209 51.6666666667 1.0666666667 +1210 51.6666666667 1.2702777778 +1211 51.7 1.32 +1212 51.7 1.19 +1213 51.6166666667 0.9152777778 +1214 51.5955555556 0.9388888889 +1215 51.6105555556 0.9805555556 +1216 51.6319444444 0.9611111111 +1217 51.6166666667 0.9152777778 +1218 51.6205555556 0.9266666667 +1219 51.6166666667 0.9152777778 +1220 51.61495 0.915875 +1221 51.6141194444 0.913075 +1222 51.6136 0.9085638889 +1223 51.6141027778 0.9064277778 +1224 51.6136972222 0.9046694444 +1225 51.6126944444 0.9015722222 +1226 51.6137333333 0.8996138889 +1227 51.6139333333 0.8951472222 +1228 51.6150694444 0.8891527778 +1229 51.6140055556 0.877525 +1230 51.6125583333 0.8742555556 +1231 51.6098166667 0.87235 +1232 51.6004694444 0.8720472222 +1233 51.5966361111 0.87065 +1234 51.5943666667 0.8677638889 +1235 51.5918861111 0.8625527778 +1236 51.5916111111 0.8590694444 +1237 51.5919 0.8508555556 +1238 51.5927583333 0.8451333333 +1239 51.5927805556 0.8405138889 +1240 51.5947222222 0.8377777778 +1241 51.5833333333 0.8383333333 +1242 51.5666666667 0.8333333333 +1243 51.5380555556 0.8011111111 +1244 51.5025 0.8541666667 +1245 51.5 0.8833333333 +1246 51.6205555556 1.2008333333 +1247 51.6205555556 0.9266666667 +1248 51.8333333333 0.9161111111 +1249 51.8108333333 0.9144444444 +1250 51.8091666667 0.98 +1251 51.8316666667 0.9811111111 +1252 51.8333333333 0.9161111111 +1253 51.0719444444 1.0738888889 +1254 51.0563888889 1.0372222222 +1255 51.0327777778 1.0197222222 +1256 51.0222222222 1.03 +1257 51.0366666667 1.0919444444 +1258 51.0719444444 1.0738888889 +1259 51.999955951 -2.8833333333 +1260 51.9997793836 -2.8888787335 +1261 51.9992515574 -2.8943652213 +1262 51.9983780795 -2.8997345145 +1263 51.9971682287 -2.9049295838 +1264 51.9956348562 -2.9098952622 +1265 51.9937942479 -2.9145788343 +1266 51.9916659511 -2.9189305979 +1267 51.9892725649 -2.9229043934 +1268 51.9866395 -2.9264580946 +1269 51.9837947065 -2.9295540548 +1270 51.9807683771 -2.9321595054 +1271 51.9775926246 -2.9342469009 +1272 51.9743011406 -2.9357942078 +1273 51.970928837 -2.9367851343 +1274 51.967511475 -2.9372092981 +1275 51.9640852856 -2.9370623318 +1276 51.9606865852 -2.9363459229 +1277 51.9573513906 -2.9350677915 +1278 51.9541150377 -2.933241602 +1279 51.9510118081 -2.9308868144 +1280 51.948074566 -2.928028473 +1281 51.9453344117 -2.9246969379 +1282 51.9428203533 -2.9209275601 +1283 51.9405590008 -2.9167603059 +1284 51.9385742856 -2.9122393324 +1285 51.9368872085 -2.90741252 +1286 51.9355156188 -2.9023309674 +1287 51.9344740267 -2.8970484519 +1288 51.9337734501 -2.8916208636 +1289 51.9334212994 -2.8861056174 +1290 51.9334212994 -2.8805610492 +1291 51.9337734501 -2.8750458031 +1292 51.9344740267 -2.8696182148 +1293 51.9355156188 -2.8643356993 +1294 51.9368872085 -2.8592541466 +1295 51.9385742856 -2.8544273343 +1296 51.9405590008 -2.8499063607 +1297 51.9428203533 -2.8457391065 +1298 51.9453344117 -2.8419697288 +1299 51.948074566 -2.8386381936 +1300 51.9510118081 -2.8357798523 +1301 51.9541150377 -2.8334250647 +1302 51.9573513906 -2.8315988752 +1303 51.9606865852 -2.8303207437 +1304 51.9640852856 -2.8296043349 +1305 51.967511475 -2.8294573685 +1306 51.970928837 -2.8298815324 +1307 51.9743011406 -2.8308724589 +1308 51.9775926246 -2.8324197658 +1309 51.9807683771 -2.8345071613 +1310 51.9837947065 -2.8371126119 +1311 51.9866395 -2.8402085721 +1312 51.9892725649 -2.8437622732 +1313 51.9916659511 -2.8477360688 +1314 51.9937942479 -2.8520878324 +1315 51.9956348562 -2.8567714045 +1316 51.9971682287 -2.8617370829 +1317 51.9983780795 -2.8669321522 +1318 51.9992515574 -2.8723014454 +1319 51.9997793836 -2.8777879332 +1320 51.999955951 -2.8833333333 +1321 51.2956888889 -2.1710333333 +1322 51.2835916667 -2.1580805556 +1323 51.2672444444 -2.11575 +1324 51.2847222222 -2.0533333333 +1325 51.3294194444 -2.0513416667 +1326 51.3487166667 -2.0694666667 +1327 51.3269444444 -2.1292833333 +1328 51.2956888889 -2.1710333333 +1329 52.5740336111 -5.3634016667 +1330 52.3368058333 -5.3641455556 +1331 52.2185361111 -5.2711694444 +1332 52.1667388889 -5.13935 +1333 52.1508333333 -5.0158333333 +1334 52.5740336111 -5.3634016667 +1335 53.05 -5.5 +1336 53.05 -5.3777222222 +1337 53.05 -5.2554444444 +1338 53.05 -5.1331666667 +1339 53.05 -5.0108888889 +1340 53.05 -4.8886111111 +1341 53.1208333333 -4.8886111111 +1342 53.2 -5.0 +1343 53.3819444444 -5.0 +1344 53.3875 -5.1713888889 +1345 53.25 -5.5 +1346 53.05 -5.5 +1347 52.8387333333 -4.8886111111 +1348 52.75 -4.8886111111 +1349 52.75 -4.6716305556 +1350 52.8387333333 -4.8886111111 +1351 53.1764722222 -5.5 +1352 53.05 -5.5 +1353 53.05 -5.3849361111 +1354 53.05 -5.2698722222 +1355 53.1764722222 -5.5 +1356 52.2100607222 -5.3787709722 +1357 52.1377777778 -5.3080555556 +1358 52.1033333333 -4.8166666667 +1359 52.14435 -4.646375 +1360 52.1508333333 -5.0158333333 +1361 52.1667388889 -5.13935 +1362 52.2100607222 -5.3787709722 +1363 52.7380555556 -5.5 +1364 52.3333333333 -5.5 +1365 52.2100607222 -5.3787709722 +1366 52.1667388889 -5.13935 +1367 52.2185361111 -5.2711694444 +1368 52.3368058333 -5.3641455556 +1369 52.5740336111 -5.3634016667 +1370 52.7380555556 -5.5 +1371 52.5 -5.3016805556 +1372 52.1508333333 -5.0158333333 +1373 52.14435 -4.646375 +1374 52.1171138889 -4.6360805556 +1375 52.1468 -4.4845083333 +1376 52.1666666667 -4.495 +1377 52.2666666667 -4.2 +1378 52.5 -4.2 +1379 52.5 -4.3377100694 +1380 52.5 -4.4754201389 +1381 52.5 -4.6131302083 +1382 52.5 -4.7508402778 +1383 52.5 -4.8885503472 +1384 52.5 -5.0262604167 +1385 52.5 -5.1639704861 +1386 52.5 -5.3016805556 +1387 53.05 -5.5 +1388 52.7380555556 -5.5 +1389 52.5 -5.3016805556 +1390 52.5 -5.1639704861 +1391 52.5 -5.0262604167 +1392 52.5 -4.8885503472 +1393 52.5 -4.7508402778 +1394 52.5 -4.6131302083 +1395 52.5 -4.4754201389 +1396 52.5 -4.3377100694 +1397 52.5 -4.2 +1398 52.5544888889 -4.2 +1399 52.75 -4.6716666667 +1400 52.75 -4.7801388889 +1401 52.75 -4.8886111111 +1402 53.05 -4.8886111111 +1403 53.05 -5.0108888889 +1404 53.05 -5.1331666667 +1405 53.05 -5.2554444444 +1406 53.05 -5.3777222222 +1407 53.05 -5.5 +1408 52.3333333333 -5.5 +1409 52.1772222222 -5.5 +1410 52.1377777778 -5.3080555556 +1411 52.3333333333 -5.5 +1412 52.2138888889 -4.3558333333 +1413 52.0052777778 -4.4219444444 +1414 52.0263888889 -4.2416666667 +1415 52.2625 -4.1661111111 +1416 52.2666666667 -4.2 +1417 52.2138888889 -4.3558333333 +1418 52.2138888889 -4.3558333333 +1419 52.0958333333 -4.3933333333 +1420 52.0555555556 -4.0619444444 +1421 52.2425 -4.0011111111 +1422 52.2666666667 -4.2 +1423 52.2138888889 -4.3558333333 +1424 52.2425 -4.0011111111 +1425 52.0555555556 -4.0619444444 +1426 52.0083333333 -3.6813888889 +1427 52.0363888889 -3.6719444444 +1428 52.0836111111 -3.5922222222 +1429 52.1225 -3.5041666667 +1430 52.1797222222 -3.5005555556 +1431 52.2425 -4.0011111111 +1432 52.14435 -4.646375 +1433 52.1336111111 -4.6911111111 +1434 52.1286290972 -4.6923695661 +1435 52.1236458923 -4.6934867815 +1436 52.118630173 -4.6941112708 +1437 52.1136003736 -4.6942409049 +1438 52.1085749736 -4.6938753744 +1439 52.1035724304 -4.6930161885 +1440 52.0986111111 -4.6916666667 +1441 51.9777777778 -4.6505555556 +1442 52.0052777778 -4.4219444444 +1443 52.2138888889 -4.3558333333 +1444 52.1666666667 -4.495 +1445 52.1468 -4.4845083333 +1446 52.1171138889 -4.6360805556 +1447 52.14435 -4.646375 +1448 52.1286111111 -3.49 +1449 52.0836111111 -3.5922222222 +1450 52.0363888889 -3.6719444444 +1451 51.9963888889 -3.6847222222 +1452 51.9708333333 -3.6597222222 +1453 51.9827777778 -3.6247222222 +1454 52.0305555556 -3.5275 +1455 52.0322222222 -3.4952777778 +1456 52.0477777778 -3.4677777778 +1457 52.0808333333 -3.4255555556 +1458 52.1036111111 -3.4458333333 +1459 52.1286111111 -3.49 +1460 52.1224776037 -0.4225 +1461 52.1223001664 -0.4264370798 +1462 52.1217716404 -0.4302901554 +1463 52.1209033022 -0.433977021 +1464 52.1197136782 -0.437419028 +1465 52.1182281473 -0.4405427677 +1466 52.1164783985 -0.4432816393 +1467 52.1145017531 -0.4455772722 +1468 52.1123403669 -0.4473807689 +1469 52.110040329 -0.4486537454 +1470 52.1076506782 -0.449369144 +1471 52.1052223559 -0.4495118043 +1472 52.1028071196 -0.4490787784 +1473 52.1004564396 -0.4480793863 +1474 52.0982204027 -0.4465350094 +1475 52.0961466457 -0.4444786278 +1476 52.0942793417 -0.4419541121 +1477 52.0926582613 -0.4390152849 +1478 52.0913179268 -0.4357247719 +1479 52.0902868787 -0.4321526683 +1480 52.0895870705 -0.4283750477 +1481 52.0892334015 -0.4244723461 +1482 52.0892334015 -0.4205276539 +1483 52.0895870705 -0.4166249523 +1484 52.0902868787 -0.4128473317 +1485 52.0913179268 -0.4092752281 +1486 52.0926582613 -0.4059847151 +1487 52.0942793417 -0.4030458879 +1488 52.0961466457 -0.4005213722 +1489 52.0982204027 -0.3984649906 +1490 52.1004564396 -0.3969206137 +1491 52.1028071196 -0.3959212216 +1492 52.1052223559 -0.3954881957 +1493 52.1076506782 -0.395630856 +1494 52.110040329 -0.3963462546 +1495 52.1123403669 -0.3976192311 +1496 52.1145017531 -0.3994227278 +1497 52.1164783985 -0.4017183607 +1498 52.1182281473 -0.4044572323 +1499 52.1197136782 -0.407580972 +1500 52.1209033022 -0.411022979 +1501 52.1217716404 -0.4147098446 +1502 52.1223001664 -0.4185629202 +1503 52.1224776037 -0.4225 +1504 52.8083333333 0.2 +1505 52.8083333333 0.3333333333 +1506 52.8833333333 0.4083333333 +1507 52.888770376 0.4035323371 +1508 52.8939769833 0.3980704212 +1509 52.8989866717 0.3921256339 +1510 52.9037831019 0.3857172013 +1511 52.9083506248 0.3788658826 +1512 52.9126743334 0.3715939029 +1513 52.916740112 0.3639248819 +1514 52.9205346833 0.3558837567 +1515 52.9240456522 0.3474967008 +1516 52.9272615471 0.338791038 +1517 52.9301718581 0.3297951528 +1518 52.9327670721 0.3205383966 +1519 52.9350387042 0.3110509909 +1520 52.9369793263 0.3013639265 +1521 52.9385825917 0.2915088612 +1522 52.9398432563 0.2815180137 +1523 52.9407571964 0.2714240568 +1524 52.941321422 0.2612600077 +1525 52.9415340873 0.2510591185 +1526 52.9413944965 0.2408547639 +1527 52.9409031063 0.2306803307 +1528 52.9400615243 0.2205691054 +1529 52.9388725038 0.2105541631 +1530 52.9373399341 0.2006682571 +1531 52.9354688284 0.1909437092 +1532 52.933265306 0.1814123023 +1533 52.9307365725 0.1721051742 +1534 52.9278908959 0.1630527144 +1535 52.9247375784 0.1542844628 +1536 52.9212869258 0.1458290125 +1537 52.9175502132 0.1377139148 +1538 52.9135396473 0.1299655892 +1539 52.9092683259 0.1226092361 +1540 52.9047501946 0.1156687551 +1541 52.9 0.1091666667 +1542 52.8083333333 0.2 +1543 52.5541666667 0.6805555556 +1544 52.5166666667 0.6666666667 +1545 52.4833333333 0.65 +1546 52.4666666667 0.75 +1547 52.4388888889 0.8083333333 +1548 52.4472222222 0.8472222222 +1549 52.5125 0.8333333333 +1550 52.5486111111 0.8 +1551 52.5555555556 0.75 +1552 52.5541666667 0.6805555556 +1553 52.9060987986 -2.22 +1554 52.9059284347 -2.2227704214 +1555 52.9054243214 -2.2254273585 +1556 52.9046071082 -2.2278619831 +1557 52.9035102684 -2.2299745875 +1558 52.9021787258 -2.2316786715 +1559 52.9006670125 -2.2329044861 +1560 52.8990370336 -2.2336018855 +1561 52.8973555298 -2.2337423743 +1562 52.8956913442 -2.233320265 +1563 52.8941126028 -2.2323529 +1564 52.8926839271 -2.230879932 +1565 52.8914637897 -2.2289616929 +1566 52.8905021241 -2.2266767188 +1567 52.8898382828 -2.2241185345 +1568 52.8894994296 -2.221391828 +1569 52.8894994296 -2.218608172 +1570 52.8898382828 -2.2158814655 +1571 52.8905021241 -2.2133232812 +1572 52.8914637897 -2.2110383071 +1573 52.8926839271 -2.209120068 +1574 52.8941126028 -2.2076471 +1575 52.8956913442 -2.206679735 +1576 52.8973555298 -2.2062576257 +1577 52.8990370336 -2.2063981145 +1578 52.9006670125 -2.2070955139 +1579 52.9021787258 -2.2083213285 +1580 52.9035102684 -2.2100254125 +1581 52.9046071082 -2.2121380169 +1582 52.9054243214 -2.2145726415 +1583 52.9059284347 -2.2172295786 +1584 52.9060987986 -2.22 +1585 52.1568465441 -1.4488888889 +1586 52.1566769462 -1.4512476826 +1587 52.1561772992 -1.4534792617 +1588 52.1553745497 -1.4554632808 +1589 52.1543119889 -1.45709276 +1590 52.1530469158 -1.4582798567 +1591 52.1516475448 -1.4589606006 +1592 52.1501893251 -1.4590983369 +1593 52.1487508716 -1.4586856924 +1594 52.1474097263 -1.4577449627 +1595 52.1462381789 -1.4563268989 +1596 52.1452993723 -1.4545079643 +1597 52.1446439021 -1.4523862089 +1598 52.1443070918 -1.4500759857 +1599 52.1443070918 -1.4477017921 +1600 52.1446439021 -1.4453915689 +1601 52.1452993723 -1.4432698135 +1602 52.1462381789 -1.4414508789 +1603 52.1474097263 -1.4400328151 +1604 52.1487508716 -1.4390920853 +1605 52.1501893251 -1.4386794409 +1606 52.1516475448 -1.4388171771 +1607 52.1530469158 -1.4394979211 +1608 52.1543119889 -1.4406850178 +1609 52.1553745497 -1.4423144969 +1610 52.1561772992 -1.4442985161 +1611 52.1566769462 -1.4465300952 +1612 52.1568465441 -1.4488888889 +1613 52.6371483654 -0.5991666667 +1614 52.6369761266 -0.6014074807 +1615 52.6364702366 -0.603507446 +1616 52.635662493 -0.6053345765 +1617 52.6346036641 -0.6067740508 +1618 52.6333602954 -0.6077354312 +1619 52.6320105244 -0.6081583435 +1620 52.6306391677 -0.6080162628 +1621 52.6293323909 -0.6073181676 +1622 52.6281722944 -0.6061079637 +1623 52.6272317572 -0.6044617146 +1624 52.6265698611 -0.6024828569 +1625 52.6262281824 -0.600295702 +1626 52.6262281824 -0.5980376314 +1627 52.6265698611 -0.5958504764 +1628 52.6272317572 -0.5938716188 +1629 52.6281722944 -0.5922253697 +1630 52.6293323909 -0.5910151658 +1631 52.6306391677 -0.5903170706 +1632 52.6320105244 -0.5901749898 +1633 52.6333602954 -0.5905979021 +1634 52.6346036641 -0.5915592825 +1635 52.635662493 -0.5929987568 +1636 52.6364702366 -0.5948258873 +1637 52.6369761266 -0.5969258527 +1638 52.6371483654 -0.5991666667 +1639 52.1146775213 -2.8016666667 +1640 52.1145009569 -2.8072262898 +1641 52.1139731394 -2.8127268489 +1642 52.113099676 -2.8181099118 +1643 52.1118898454 -2.8233183024 +1644 52.1103564987 -2.828296712 +1645 52.1085159218 -2.8329922895 +1646 52.1063876615 -2.8373552052 +1647 52.103994317 -2.8413391811 +1648 52.1013612984 -2.8449019829 +1649 52.0985165558 -2.8480058678 +1650 52.0954902813 -2.8506179835 +1651 52.0923145874 -2.8527107142 +1652 52.089023165 -2.8542619706 +1653 52.0856509256 -2.8552554197 +1654 52.0822336298 -2.8556806534 +1655 52.0788075078 -2.8555332935 +1656 52.0754088753 -2.854815033 +1657 52.0720737483 -2.8535336121 +1658 52.0688374621 -2.851702731 +1659 52.0657342973 -2.8493419001 +1660 52.0627971173 -2.8464762284 +1661 52.0600570218 -2.8431361539 +1662 52.0575430179 -2.8393571186 +1663 52.0552817149 -2.835179191 +1664 52.0532970434 -2.8306466414 +1665 52.0516100039 -2.8258074726 +1666 52.0502384449 -2.8207129137 +1667 52.0491968762 -2.8154168795 +1668 52.0484963154 -2.8099754026 +1669 52.0481441727 -2.8044460442 +1670 52.0481441727 -2.7988872891 +1671 52.0484963154 -2.7933579308 +1672 52.0491968762 -2.7879164539 +1673 52.0502384449 -2.7826204196 +1674 52.0516100039 -2.7775258607 +1675 52.0532970434 -2.772686692 +1676 52.0552817149 -2.7681541423 +1677 52.0575430179 -2.7639762147 +1678 52.0600570218 -2.7601971794 +1679 52.0627971173 -2.7568571049 +1680 52.0657342973 -2.7539914332 +1681 52.0688374621 -2.7516306023 +1682 52.0720737483 -2.7497997213 +1683 52.0754088753 -2.7485183003 +1684 52.0788075078 -2.7478000398 +1685 52.0822336298 -2.74765268 +1686 52.0856509256 -2.7480779137 +1687 52.089023165 -2.7490713628 +1688 52.0923145874 -2.7506226191 +1689 52.0954902813 -2.7527153499 +1690 52.0985165558 -2.7553274655 +1691 52.1013612984 -2.7584313504 +1692 52.103994317 -2.7619941522 +1693 52.1063876615 -2.7659781281 +1694 52.1085159218 -2.7703410438 +1695 52.1103564987 -2.7750366213 +1696 52.1118898454 -2.7800150309 +1697 52.113099676 -2.7852234215 +1698 52.1139731394 -2.7906064844 +1699 52.1145009569 -2.7961070436 +1700 52.1146775213 -2.8016666667 +1701 52.8395527778 -4.0894944444 +1702 52.8415168258 -4.0949801674 +1703 52.8431637779 -4.1007438086 +1704 52.8444800679 -4.1067350168 +1705 52.8454543458 -4.1129021488 +1706 52.84607821 -4.1191920321 +1707 52.8463462805 -4.1255504268 +1708 52.8462562454 -4.131922497 +1709 52.8458088811 -4.1382532879 +1710 52.8450080457 -4.1444882038 +1711 52.8438606453 -4.1505734827 +1712 52.8423765741 -4.1564566639 +1713 52.8405686282 -4.1620870429 +1714 52.8384523943 -4.1674161122 +1715 52.8360461149 -4.1723979807 +1716 52.8333705291 -4.1769897708 +1717 52.8304486936 -4.1811519882 +1718 52.8273057818 -4.184848862 +1719 52.8239688666 -4.188048651 +1720 52.8204666854 -4.1907239156 +1721 52.8168293921 -4.1928517505 +1722 52.813088296 -4.1944139782 +1723 52.8092755921 -4.1953973017 +1724 52.8054240831 -4.1957934135 +1725 52.8015668967 -4.1955990621 +1726 52.7977372011 -4.1948160749 +1727 52.7939679192 -4.1934513366 +1728 52.7902914462 -4.1915167256 +1729 52.7867393717 -4.189029006 +1730 52.783342209 -4.1860096801 +1731 52.7801291336 -4.1824847989 +1732 52.7771277339 -4.1784847357 +1733 52.7743637754 -4.1740439228 +1734 52.7718609805 -4.169200554 +1735 52.7696408264 -4.1639962563 +1736 52.7677223618 -4.1584757326 +1737 52.7661220445 -4.1526863794 +1738 52.7648536015 -4.1466778812 +1739 52.763927912 -4.1405017878 +1740 52.7633529149 -4.134211074 +1741 52.7631335411 -4.1278596898 +1742 52.7632716721 -4.1215021006 +1743 52.7637661231 -4.115192825 +1744 52.764612654 -4.1089859706 +1745 52.7658040048 -4.1029347739 +1746 52.7673299578 -4.0970911477 +1747 52.7691774242 -4.0915052387 +1748 52.7713305556 -4.086225 +1749 52.8395527778 -4.0894944444 +1750 52.8850805556 -4.1630888889 +1751 52.8834892012 -4.1716703219 +1752 52.8815618217 -4.1800610524 +1753 52.879307044 -4.1882253836 +1754 52.8767345124 -4.1961284314 +1755 52.8738552286 -4.203736446 +1756 52.8706815036 -4.2110169583 +1757 52.8672269048 -4.2179389192 +1758 52.8635061966 -4.2244728329 +1759 52.8595352771 -4.2305908832 +1760 52.8553311089 -4.2362670523 +1761 52.8509116461 -4.2414772309 +1762 52.8462957566 -4.24619932 +1763 52.8415031405 -4.2504133239 +1764 52.836554246 -4.2541014336 +1765 52.8314701808 -4.2572481003 +1766 52.8262726218 -4.2598400991 +1767 52.8209837219 -4.2618665826 +1768 52.8156260152 -4.2633191239 +1769 52.8102223209 -4.2641917489 +1770 52.8047956454 -4.2644809586 +1771 52.7993690845 -4.2641857397 +1772 52.7939657248 -4.263307566 +1773 52.788608546 -4.2618503879 +1774 52.7833203228 -4.2598206119 +1775 52.7781235288 -4.2572270704 +1776 52.7730402409 -4.2540809803 +1777 52.7680920465 -4.2503958922 +1778 52.763299952 -4.2461876305 +1779 52.7586842944 -4.2414742231 +1780 52.7542646557 -4.236275823 +1781 52.7500597804 -4.2306146206 +1782 52.7460874972 -4.2245147485 +1783 52.7423646436 -4.2180021779 +1784 52.7389069959 -4.2111046078 +1785 52.735729203 -4.2038513475 +1786 52.732844725 -4.1962731925 +1787 52.7302657772 -4.1884022946 +1788 52.7280032789 -4.180272027 +1789 52.7260668081 -4.1719168439 +1790 52.7244645613 -4.1633721365 +1791 52.7232033196 -4.1546740851 +1792 52.7222884205 -4.1458595084 +1793 52.7217237352 -4.1369657097 +1794 52.7215116532 -4.1280303217 +1795 52.7216530717 -4.1190911504 +1796 52.7221473925 -4.1101860173 +1797 52.7229925239 -4.1013526024 +1798 52.7241848898 -4.0926282873 +1799 52.7257194444 -4.08405 +1800 52.7713305556 -4.086225 +1801 52.7692223853 -4.0913879573 +1802 52.7674051858 -4.0968429653 +1803 52.7658950291 -4.1025466245 +1804 52.7647043103 -4.1084520974 +1805 52.763842802 -4.1145109035 +1806 52.763317574 -4.1206733141 +1807 52.7631329367 -4.1268887576 +1808 52.7632904051 -4.1331062308 +1809 52.7637886869 -4.1392747141 +1810 52.7646236933 -4.1453435863 +1811 52.7657885717 -4.1512630371 +1812 52.7672737619 -4.1569844719 +1813 52.7690670735 -4.1624609086 +1814 52.7711537858 -4.1676473604 +1815 52.7735167672 -4.1725012037 +1816 52.7761366151 -4.1769825268 +1817 52.7789918139 -4.1810544573 +1818 52.7820589112 -4.1846834655 +1819 52.7853127087 -4.1878396407 +1820 52.7887264686 -4.1904969392 +1821 52.7922721322 -4.1926334009 +1822 52.7959205499 -4.1942313326 +1823 52.7996417197 -4.1952774577 +1824 52.803405034 -4.1957630298 +1825 52.8071795305 -4.1956839083 +1826 52.8109341468 -4.1950405983 +1827 52.8146379764 -4.1938382505 +1828 52.818260523 -4.1920866238 +1829 52.8217719521 -4.1898000094 +1830 52.8251433373 -4.1869971173 +1831 52.8283468994 -4.1837009258 +1832 52.8313562361 -4.1799384954 +1833 52.8341465404 -4.1757407482 +1834 52.8366948064 -4.1711422147 +1835 52.8389800201 -4.16618075 +1836 52.8409833333 -4.1608972222 +1837 52.8850805556 -4.1630888889 +1838 52.8282916667 -4.183775 +1839 52.7062027778 -4.3215111111 +1840 52.6592083333 -4.2084722222 +1841 52.7675166667 -4.0860444444 +1842 52.7713305556 -4.086225 +1843 52.7692187011 -4.0913798344 +1844 52.7674020804 -4.0968320407 +1845 52.7658921562 -4.1025326866 +1846 52.7647013069 -4.1084350162 +1847 52.7638392941 -4.1144906333 +1848 52.7633131834 -4.1206498956 +1849 52.763127287 -4.1268623184 +1850 52.7632831285 -4.1330769853 +1851 52.7637794307 -4.1392429612 +1852 52.7646121256 -4.145309707 +1853 52.7657743881 -4.1512274901 +1854 52.7672566908 -4.1569477885 +1855 52.7690468821 -4.1624236863 +1856 52.7711302844 -4.167610256 +1857 52.7734898141 -4.1724649246 +1858 52.7761061204 -4.1769478222 +1859 52.7789577431 -4.1810221083 +1860 52.7820212872 -4.1846542748 +1861 52.7852716143 -4.1878144214 +1862 52.7886820476 -4.1904765038 +1863 52.7922245896 -4.1926185491 +1864 52.7958701517 -4.1942228402 +1865 52.799588792 -4.1952760644 +1866 52.8033499607 -4.1957694276 +1867 52.8071227506 -4.1956987304 +1868 52.8108761513 -4.195064408 +1869 52.8145793036 -4.193871531 +1870 52.818201754 -4.1921297686 +1871 52.8217137049 -4.1898533133 +1872 52.8250862609 -4.1870607687 +1873 52.8282916667 -4.183775 +1874 52.7062027778 -4.3215111111 +1875 52.6376388889 -4.3995916667 +1876 52.5906805556 -4.2867416667 +1877 52.6592083333 -4.2084722222 +1878 52.7062027778 -4.3215111111 +1879 52.8851638889 -4.0916888889 +1880 52.7257194444 -4.08405 +1881 52.7276026422 -4.0755987733 +1882 52.7298184726 -4.0673688901 +1883 52.7323568761 -4.0593953848 +1884 52.7352069624 -4.0517125112 +1885 52.738356502 -4.0443532948 +1886 52.7417919777 -4.037349392 +1887 52.7454986418 -4.030730955 +1888 52.7494605784 -4.0245265029 +1889 52.7536607714 -4.0187627984 +1890 52.7580811762 -4.0134647331 +1891 52.7627027967 -4.0086552188 +1892 52.7675057658 -4.0043550877 +1893 52.7724694303 -4.0005830012 +1894 52.7775724392 -3.9973553675 +1895 52.7827928341 -3.9946862679 +1896 52.7881081439 -3.9925873936 +1897 52.7934954808 -3.9910679921 +1898 52.7989316381 -3.9901348241 +1899 52.8043931904 -3.9897921305 +1900 52.8098565941 -3.9900416104 +1901 52.8152982887 -3.9908824103 +1902 52.8206947986 -3.9923111235 +1903 52.8260228348 -3.9943218012 +1904 52.831259395 -3.9969059746 +1905 52.8363818638 -4.0000526878 +1906 52.8413681109 -4.0037485419 +1907 52.8461965867 -4.0079777498 +1908 52.8508464167 -4.0127222017 +1909 52.8552974922 -4.0179615407 +1910 52.8595305579 -4.0236732496 +1911 52.8635272962 -4.0298327457 +1912 52.8672704074 -4.0364134868 +1913 52.8707436851 -4.0433870849 +1914 52.8739320877 -4.0507234291 +1915 52.8768218039 -4.0583908159 +1916 52.8794003139 -4.0663560872 +1917 52.8816564439 -4.0745847751 +1918 52.8835804155 -4.0830412523 +1919 52.8851638889 -4.0916888889 +1920 52.8850805556 -4.1630888889 +1921 52.8409833333 -4.1608972222 +1922 52.8426949429 -4.1553132526 +1923 52.8440909498 -4.149494417 +1924 52.8451603374 -4.143489638 +1925 52.8458942118 -4.1373488445 +1926 52.8462864694 -4.131123106 +1927 52.8463338475 -4.1248642045 +1928 52.8460359521 -4.1186242003 +1929 52.8453952609 -4.1124549952 +1930 52.8444171027 -4.1064078968 +1931 52.8431096128 -4.100533189 +1932 52.8414836643 -4.0948797102 +1933 52.8395527778 -4.0894944444 +1934 52.8851638889 -4.0916888889 +1935 52.886398031 -4.1004821132 +1936 52.8872810751 -4.1093902725 +1937 52.8878082526 -4.118375237 +1938 52.8879772819 -4.1273981205 +1939 52.8877874313 -4.13641987 +1940 52.8872395227 -4.1454014374 +1941 52.8863359272 -4.1543039514 +1942 52.8850805556 -4.1630888889 +1943 52.8395527778 -4.0894944444 +1944 52.8415168258 -4.0949801674 +1945 52.8431637779 -4.1007438086 +1946 52.8444800679 -4.1067350168 +1947 52.8454543458 -4.1129021488 +1948 52.84607821 -4.1191920321 +1949 52.8463462805 -4.1255504268 +1950 52.8462562454 -4.131922497 +1951 52.8458088811 -4.1382532879 +1952 52.8450080457 -4.1444882038 +1953 52.8438606453 -4.1505734827 +1954 52.8423765741 -4.1564566639 +1955 52.8405686282 -4.1620870429 +1956 52.8384523943 -4.1674161122 +1957 52.8360461149 -4.1723979807 +1958 52.8333705291 -4.1769897708 +1959 52.8304486936 -4.1811519882 +1960 52.8273057818 -4.184848862 +1961 52.8239688666 -4.188048651 +1962 52.8204666854 -4.1907239156 +1963 52.8168293921 -4.1928517505 +1964 52.813088296 -4.1944139782 +1965 52.8092755921 -4.1953973017 +1966 52.8054240831 -4.1957934135 +1967 52.8015668967 -4.1955990621 +1968 52.7977372011 -4.1948160749 +1969 52.7939679192 -4.1934513366 +1970 52.7902914462 -4.1915167256 +1971 52.7867393717 -4.189029006 +1972 52.783342209 -4.1860096801 +1973 52.7801291336 -4.1824847989 +1974 52.7771277339 -4.1784847357 +1975 52.7743637754 -4.1740439228 +1976 52.7718609805 -4.169200554 +1977 52.7696408264 -4.1639962563 +1978 52.7677223618 -4.1584757326 +1979 52.7661220445 -4.1526863794 +1980 52.7648536015 -4.1466778812 +1981 52.763927912 -4.1405017878 +1982 52.7633529149 -4.134211074 +1983 52.7631335411 -4.1278596898 +1984 52.7632716721 -4.1215021006 +1985 52.7637661231 -4.115192825 +1986 52.764612654 -4.1089859706 +1987 52.7658040048 -4.1029347739 +1988 52.7673299578 -4.0970911477 +1989 52.7691774242 -4.0915052387 +1990 52.7713305556 -4.086225 +1991 52.8395527778 -4.0894944444 +1992 52.8850805556 -4.1630888889 +1993 52.8834892012 -4.1716703219 +1994 52.8815618217 -4.1800610524 +1995 52.879307044 -4.1882253836 +1996 52.8767345124 -4.1961284314 +1997 52.8738552286 -4.203736446 +1998 52.8706815036 -4.2110169583 +1999 52.8672269048 -4.2179389192 +2000 52.8635061966 -4.2244728329 +2001 52.8595352771 -4.2305908832 +2002 52.8553311089 -4.2362670523 +2003 52.8509116461 -4.2414772309 +2004 52.8462957566 -4.24619932 +2005 52.8415031405 -4.2504133239 +2006 52.836554246 -4.2541014336 +2007 52.8314701808 -4.2572481003 +2008 52.8262726218 -4.2598400991 +2009 52.8209837219 -4.2618665826 +2010 52.8156260152 -4.2633191239 +2011 52.8102223209 -4.2641917489 +2012 52.8047956454 -4.2644809586 +2013 52.7993690845 -4.2641857397 +2014 52.7939657248 -4.263307566 +2015 52.788608546 -4.2618503879 +2016 52.7833203228 -4.2598206119 +2017 52.7781235288 -4.2572270704 +2018 52.7730402409 -4.2540809803 +2019 52.7680920465 -4.2503958922 +2020 52.763299952 -4.2461876305 +2021 52.7586842944 -4.2414742231 +2022 52.7542646557 -4.236275823 +2023 52.7500597804 -4.2306146206 +2024 52.7460874972 -4.2245147485 +2025 52.7423646436 -4.2180021779 +2026 52.7389069959 -4.2111046078 +2027 52.735729203 -4.2038513475 +2028 52.732844725 -4.1962731925 +2029 52.7302657772 -4.1884022946 +2030 52.7280032789 -4.180272027 +2031 52.7260668081 -4.1719168439 +2032 52.7244645613 -4.1633721365 +2033 52.7232033196 -4.1546740851 +2034 52.7222884205 -4.1458595084 +2035 52.7217237352 -4.1369657097 +2036 52.7215116532 -4.1280303217 +2037 52.7216530717 -4.1190911504 +2038 52.7221473925 -4.1101860173 +2039 52.7229925239 -4.1013526024 +2040 52.7241848898 -4.0926282873 +2041 52.7257194444 -4.08405 +2042 52.7713305556 -4.086225 +2043 52.7692223853 -4.0913879573 +2044 52.7674051858 -4.0968429653 +2045 52.7658950291 -4.1025466245 +2046 52.7647043103 -4.1084520974 +2047 52.763842802 -4.1145109035 +2048 52.763317574 -4.1206733141 +2049 52.7631329367 -4.1268887576 +2050 52.7632904051 -4.1331062308 +2051 52.7637886869 -4.1392747141 +2052 52.7646236933 -4.1453435863 +2053 52.7657885717 -4.1512630371 +2054 52.7672737619 -4.1569844719 +2055 52.7690670735 -4.1624609086 +2056 52.7711537858 -4.1676473604 +2057 52.7735167672 -4.1725012037 +2058 52.7761366151 -4.1769825268 +2059 52.7789918139 -4.1810544573 +2060 52.7820589112 -4.1846834655 +2061 52.7853127087 -4.1878396407 +2062 52.7887264686 -4.1904969392 +2063 52.7922721322 -4.1926334009 +2064 52.7959205499 -4.1942313326 +2065 52.7996417197 -4.1952774577 +2066 52.803405034 -4.1957630298 +2067 52.8071795305 -4.1956839083 +2068 52.8109341468 -4.1950405983 +2069 52.8146379764 -4.1938382505 +2070 52.818260523 -4.1920866238 +2071 52.8217719521 -4.1898000094 +2072 52.8251433373 -4.1869971173 +2073 52.8283468994 -4.1837009258 +2074 52.8313562361 -4.1799384954 +2075 52.8341465404 -4.1757407482 +2076 52.8366948064 -4.1711422147 +2077 52.8389800201 -4.16618075 +2078 52.8409833333 -4.1608972222 +2079 52.8850805556 -4.1630888889 +2080 52.8282916667 -4.183775 +2081 52.7062027778 -4.3215111111 +2082 52.6592083333 -4.2084722222 +2083 52.7675166667 -4.0860444444 +2084 52.7713305556 -4.086225 +2085 52.7692187011 -4.0913798344 +2086 52.7674020804 -4.0968320407 +2087 52.7658921562 -4.1025326866 +2088 52.7647013069 -4.1084350162 +2089 52.7638392941 -4.1144906333 +2090 52.7633131834 -4.1206498956 +2091 52.763127287 -4.1268623184 +2092 52.7632831285 -4.1330769853 +2093 52.7637794307 -4.1392429612 +2094 52.7646121256 -4.145309707 +2095 52.7657743881 -4.1512274901 +2096 52.7672566908 -4.1569477885 +2097 52.7690468821 -4.1624236863 +2098 52.7711302844 -4.167610256 +2099 52.7734898141 -4.1724649246 +2100 52.7761061204 -4.1769478222 +2101 52.7789577431 -4.1810221083 +2102 52.7820212872 -4.1846542748 +2103 52.7852716143 -4.1878144214 +2104 52.7886820476 -4.1904765038 +2105 52.7922245896 -4.1926185491 +2106 52.7958701517 -4.1942228402 +2107 52.799588792 -4.1952760644 +2108 52.8033499607 -4.1957694276 +2109 52.8071227506 -4.1956987304 +2110 52.8108761513 -4.195064408 +2111 52.8145793036 -4.193871531 +2112 52.818201754 -4.1921297686 +2113 52.8217137049 -4.1898533133 +2114 52.8250862609 -4.1870607687 +2115 52.8282916667 -4.183775 +2116 52.8851638889 -4.0916888889 +2117 52.7257194444 -4.08405 +2118 52.7276026422 -4.0755987733 +2119 52.7298184726 -4.0673688901 +2120 52.7323568761 -4.0593953848 +2121 52.7352069624 -4.0517125112 +2122 52.738356502 -4.0443532948 +2123 52.7417919777 -4.037349392 +2124 52.7454986418 -4.030730955 +2125 52.7494605784 -4.0245265029 +2126 52.7536607714 -4.0187627984 +2127 52.7580811762 -4.0134647331 +2128 52.7627027967 -4.0086552188 +2129 52.7675057658 -4.0043550877 +2130 52.7724694303 -4.0005830012 +2131 52.7775724392 -3.9973553675 +2132 52.7827928341 -3.9946862679 +2133 52.7881081439 -3.9925873936 +2134 52.7934954808 -3.9910679921 +2135 52.7989316381 -3.9901348241 +2136 52.8043931904 -3.9897921305 +2137 52.8098565941 -3.9900416104 +2138 52.8152982887 -3.9908824103 +2139 52.8206947986 -3.9923111235 +2140 52.8260228348 -3.9943218012 +2141 52.831259395 -3.9969059746 +2142 52.8363818638 -4.0000526878 +2143 52.8413681109 -4.0037485419 +2144 52.8461965867 -4.0079777498 +2145 52.8508464167 -4.0127222017 +2146 52.8552974922 -4.0179615407 +2147 52.8595305579 -4.0236732496 +2148 52.8635272962 -4.0298327457 +2149 52.8672704074 -4.0364134868 +2150 52.8707436851 -4.0433870849 +2151 52.8739320877 -4.0507234291 +2152 52.8768218039 -4.0583908159 +2153 52.8794003139 -4.0663560872 +2154 52.8816564439 -4.0745847751 +2155 52.8835804155 -4.0830412523 +2156 52.8851638889 -4.0916888889 +2157 52.8850805556 -4.1630888889 +2158 52.8409833333 -4.1608972222 +2159 52.8426949429 -4.1553132526 +2160 52.8440909498 -4.149494417 +2161 52.8451603374 -4.143489638 +2162 52.8458942118 -4.1373488445 +2163 52.8462864694 -4.131123106 +2164 52.8463338475 -4.1248642045 +2165 52.8460359521 -4.1186242003 +2166 52.8453952609 -4.1124549952 +2167 52.8444171027 -4.1064078968 +2168 52.8431096128 -4.100533189 +2169 52.8414836643 -4.0948797102 +2170 52.8395527778 -4.0894944444 +2171 52.8851638889 -4.0916888889 +2172 52.886398031 -4.1004821132 +2173 52.8872810751 -4.1093902725 +2174 52.8878082526 -4.118375237 +2175 52.8879772819 -4.1273981205 +2176 52.8877874313 -4.13641987 +2177 52.8872395227 -4.1454014374 +2178 52.8863359272 -4.1543039514 +2179 52.8850805556 -4.1630888889 +2180 51.80407725 -1.5951848611 +2181 51.7955109722 -1.9976505556 +2182 51.6860482222 -1.9911186944 +2183 51.6661864444 -1.8215250833 +2184 51.6709806111 -1.58842725 +2185 51.80407725 -1.5951848611 +2186 52.0883218333 -2.0679103333 +2187 51.8948650833 -2.3588221389 +2188 51.8169415833 -2.0686747222 +2189 51.7969642778 -1.9337063889 +2190 51.8007185 -1.76084275 +2191 52.0883218333 -2.0679103333 +2192 52.2592760556 -2.2526999167 +2193 52.0214293333 -2.6449074167 +2194 51.9502352778 -2.567252 +2195 51.8948650833 -2.3588221389 +2196 52.0883218333 -2.0679103333 +2197 52.2592760556 -2.2526999167 +2198 52.5495711667 -2.5705153611 +2199 52.4352228333 -2.8549897222 +2200 52.2284006944 -2.8724085833 +2201 52.0214293333 -2.6449074167 +2202 52.2592760556 -2.2526999167 +2203 52.5495711667 -2.5705153611 +2204 53.1891285695 -1.9583333333 +2205 53.1889532633 -1.9632487194 +2206 53.1884298098 -1.9680949854 +2207 53.1875655697 -1.9728039882 +2208 53.1863726948 -1.9773095245 +2209 53.1848679569 -1.9815482657 +2210 53.1830725106 -1.9854606515 +2211 53.1810115942 -1.9889917292 +2212 53.1787141743 -1.9920919267 +2213 53.1762125364 -1.994717749 +2214 53.1735418303 -1.9968323868 +2215 53.1707395745 -1.9984062307 +2216 53.1678451281 -1.9994172825 +2217 53.1648991371 -1.9998514587 +2218 53.1619429631 -1.9997027821 +2219 53.159018102 -1.9989734591 +2220 53.1561656021 -1.9976738419 +2221 53.1534254881 -1.995822277 +2222 53.1508362003 -1.9934448418 +2223 53.1484340564 -1.990574974 +2224 53.1462527437 -1.9872529981 +2225 53.1443228474 -1.983525558 +2226 53.1426714238 -1.9794449609 +2227 53.1413216224 -1.9750684446 +2228 53.1402923625 -1.9704573761 +2229 53.1395980694 -1.9656763943 +2230 53.1392484733 -1.9607925076 +2231 53.1392484733 -1.9558741591 +2232 53.1395980694 -1.9509902724 +2233 53.1402923625 -1.9462092906 +2234 53.1413216224 -1.9415982221 +2235 53.1426714238 -1.9372217058 +2236 53.1443228474 -1.9331411087 +2237 53.1462527437 -1.9294136686 +2238 53.1484340564 -1.9260916927 +2239 53.1508362003 -1.9232218248 +2240 53.1534254881 -1.9208443897 +2241 53.1561656021 -1.9189928248 +2242 53.159018102 -1.9176932075 +2243 53.1619429631 -1.9169638845 +2244 53.1648991371 -1.916815208 +2245 53.1678451281 -1.9172493842 +2246 53.1707395745 -1.918260436 +2247 53.1735418303 -1.9198342799 +2248 53.1762125364 -1.9219489177 +2249 53.1787141743 -1.9245747399 +2250 53.1810115942 -1.9276749375 +2251 53.1830725106 -1.9312060152 +2252 53.1848679569 -1.935118401 +2253 53.1863726948 -1.9393571422 +2254 53.1875655697 -1.9438626785 +2255 53.1884298098 -1.9485716812 +2256 53.1889532633 -1.9534179472 +2257 53.1891285695 -1.9583333333 +2258 53.0983333333 -0.6927777778 +2259 53.0927777778 -0.7047222222 +2260 53.0744444444 -0.7013888889 +2261 53.0741666667 -0.6788888889 +2262 53.095 -0.6761111111 +2263 53.0983333333 -0.6927777778 +2264 53.3919444444 0.2316666667 +2265 53.3925294729 0.2406825788 +2266 53.3934738632 0.2496135246 +2267 53.3947627808 0.2584233162 +2268 53.3963907993 0.2670748532 +2269 53.398351064 0.2755316902 +2270 53.4006353204 0.283758188 +2271 53.4032339479 0.2917196616 +2272 53.4061360005 0.299382525 +2273 53.4093292513 0.3067144306 +2274 53.4128002441 0.3136844052 +2275 53.4165343486 0.3202629797 +2276 53.4205158216 0.3264223132 +2277 53.4247278727 0.3321363105 +2278 53.4291527337 0.3373807333 +2279 53.4337717333 0.3421333029 +2280 53.4385653748 0.3463737964 +2281 53.4435134178 0.3500841336 +2282 53.4485949627 0.353248456 +2283 53.4537885386 0.3558531959 +2284 53.4590721933 0.3578871374 +2285 53.4644235858 0.3593414664 +2286 53.4698200802 0.3602098119 +2287 53.4752388414 0.360488276 +2288 53.4806569311 0.3601754547 +2289 53.4860514054 0.3592724472 +2290 53.4913994117 0.3577828553 +2291 53.4966782858 0.3557127719 +2292 53.501865648 0.3530707587 +2293 53.5069394986 0.3498678134 +2294 53.5118783116 0.3461173266 +2295 53.5166611264 0.3418350278 +2296 53.5212676377 0.3370389214 +2297 53.5256782822 0.3317492124 +2298 53.5298743225 0.3259882231 +2299 53.5338379274 0.3197802995 +2300 53.5375522487 0.313151709 +2301 53.5410014936 0.3061305297 +2302 53.5441709927 0.2987465312 +2303 53.5470472631 0.2910310476 +2304 53.5496180668 0.2830168442 +2305 53.5518724632 0.2747379765 +2306 53.5538008569 0.2662296443 +2307 53.5553950386 0.2575280401 +2308 53.556648221 0.2486701928 +2309 53.5575550683 0.2396938079 +2310 53.5581117187 0.2306371044 +2311 53.5583158018 0.2215386491 +2312 53.5581664484 0.2124371901 +2313 53.5576642946 0.2033714882 +2314 53.5568114788 0.1943801493 +2315 53.5556116326 0.1855014572 +2316 53.554069865 0.1767732078 +2317 53.5521927402 0.1682325452 +2318 53.5499882492 0.1599158018 +2319 53.5474657756 0.1518583412 +2320 53.5446360542 0.144094406 +2321 53.5415111256 0.1366569705 +2322 53.5381042833 0.1295775996 +2323 53.5344300172 0.1228863138 +2324 53.5305039502 0.116611461 +2325 53.5263427719 0.1107795966 +2326 53.5219641659 0.1054153713 +2327 53.5173867345 0.1005414271 +2328 53.5126299184 0.0961783027 +2329 53.5077139136 0.0923443485 +2330 53.5026595851 0.0890556509 +2331 53.4974883771 0.0863259664 +2332 53.4922222222 0.0841666667 +2333 53.3919444444 0.2316666667 +2334 53.2369316665 -1.9244444444 +2335 53.2367613117 -1.9272361795 +2336 53.2362572255 -1.9299135563 +2337 53.2354400564 -1.932366909 +2338 53.2343432761 -1.9344957623 +2339 53.233011806 -1.9362129508 +2340 53.2315001758 -1.9374481891 +2341 53.2298702871 -1.9381509465 +2342 53.2281888772 -1.9382925095 +2343 53.2265247852 -1.9378671475 +2344 53.2249461335 -1.9368923376 +2345 53.2235175393 -1.9354080383 +2346 53.2222974722 -1.9334750457 +2347 53.2213358622 -1.9311725002 +2348 53.2206720594 -1.9285946453 +2349 53.2203332259 -1.9258469737 +2350 53.2203332259 -1.9230419152 +2351 53.2206720594 -1.9202942436 +2352 53.2213358622 -1.9177163887 +2353 53.2222974722 -1.9154138432 +2354 53.2235175393 -1.9134808506 +2355 53.2249461335 -1.9119965513 +2356 53.2265247852 -1.9110217413 +2357 53.2281888772 -1.9105963794 +2358 53.2298702871 -1.9107379424 +2359 53.2315001758 -1.9114406998 +2360 53.233011806 -1.9126759381 +2361 53.2343432761 -1.9143931266 +2362 53.2354400564 -1.9165219799 +2363 53.2362572255 -1.9189753326 +2364 53.2367613117 -1.9216527094 +2365 53.2369316665 -1.9244444444 +2366 55.2861722222 0.2412277778 +2367 54.9623333333 -0.9158333333 +2368 54.8112972222 -0.9156 +2369 54.5171138889 -0.5256138889 +2370 55.0285222222 1.298075 +2371 55.2861722222 0.2412277778 +2372 55.0285222222 1.298075 +2373 54.5171138889 -0.5256138889 +2374 54.24745 -0.1744611111 +2375 54.8496888889 2.0026916667 +2376 55.0285222222 1.298075 +2377 54.8496888889 2.0026916667 +2378 54.24745 -0.1744611111 +2379 54.1121805556 -0.0005361111 +2380 54.75875 2.3526361111 +2381 54.8496888889 2.0026916667 +2382 54.75875 2.3526361111 +2383 54.1121805556 -0.0005361111 +2384 53.6369388889 0.599175 +2385 54.2940166667 3.0193416667 +2386 54.5285361111 2.9095444444 +2387 54.6632333333 2.7144361111 +2388 54.75875 2.3526361111 +2389 54.2940166667 3.0193416667 +2390 53.6369388889 0.599175 +2391 53.4686111111 2.7113888889 +2392 53.9263888889 2.9538888889 +2393 54.2925722222 3.0200138889 +2394 54.2940166667 3.0193416667 +2395 54.9623333333 -0.9158333333 +2396 54.9202777778 -1.0619444444 +2397 54.8694444444 -1.1375 +2398 54.7081583333 -1.2140305556 +2399 54.4006611111 -0.9216388889 +2400 54.8112972222 -0.9156 +2401 54.9623333333 -0.9158333333 +2402 54.8112972222 -0.9156 +2403 54.4006611111 -0.9216388889 +2404 54.5171138889 -0.5256138889 +2405 54.8112972222 -0.9156 +2406 54.5171138889 -0.5256138889 +2407 54.4006611111 -0.9216388889 +2408 54.1240138889 -0.5964777778 +2409 54.24745 -0.1744611111 +2410 54.5171138889 -0.5256138889 +2411 54.24745 -0.1744611111 +2412 54.1240138889 -0.5964777778 +2413 53.9855666667 -0.4349 +2414 54.1121805556 -0.0005361111 +2415 54.24745 -0.1744611111 +2416 54.1121805556 -0.0005361111 +2417 53.9855666667 -0.4349 +2418 53.7253805556 -0.1348055556 +2419 53.6369388889 0.599175 +2420 54.1121805556 -0.0005361111 +2421 55.4081972222 0.8311305556 +2422 55.2861722222 0.2412277778 +2423 55.0285222222 1.298075 +2424 55.1621805556 1.7996194444 +2425 55.4081972222 0.8311305556 +2426 55.1621805556 1.7996194444 +2427 55.0285222222 1.298075 +2428 54.8496888889 2.0026916667 +2429 54.9777948889 2.4938992222 +2430 55.1621805556 1.7996194444 +2431 54.9777948889 2.4938992222 +2432 54.8496888889 2.0026916667 +2433 54.75875 2.3526361111 +2434 54.8308915833 2.6309753889 +2435 54.9777948889 2.4938992222 +2436 54.8308915833 2.6309753889 +2437 54.75875 2.3526361111 +2438 54.6632333333 2.7144361111 +2439 54.5285361111 2.9095444444 +2440 54.8308915833 2.6309753889 +2441 55.5631527778 1.6068611111 +2442 55.4081972222 0.8311305556 +2443 55.1621805556 1.7996194444 +2444 55.2711027778 2.2167416667 +2445 55.5305138889 1.9394305556 +2446 55.5631527778 1.6068611111 +2447 55.2711027778 2.2167416667 +2448 55.1621805556 1.7996194444 +2449 54.9777948889 2.4938992222 +2450 55.2711027778 2.2167416667 +2451 53.2493170173 -0.5238888889 +2452 53.2491385233 -0.5329620222 +2453 53.2486038102 -0.5419960775 +2454 53.2477151807 -0.5509521479 +2455 53.2464764618 -0.5597916681 +2456 53.2448929879 -0.5684765836 +2457 53.2429715769 -0.5769695164 +2458 53.2407205011 -0.5852339289 +2459 53.2381494508 -0.5932342833 +2460 53.2352694915 -0.6009361957 +2461 53.2320930161 -0.6083065862 +2462 53.2286336905 -0.6153138218 +2463 53.2249063941 -0.6219278531 +2464 53.2209271548 -0.6281203442 +2465 53.2167130794 -0.6338647934 +2466 53.2122822792 -0.6391366472 +2467 53.2076537911 -0.6439134041 +2468 53.202847495 -0.6481747101 +2469 53.197884028 -0.6519024438 +2470 53.1927846947 -0.6550807917 +2471 53.1875713753 -0.6576963139 +2472 53.182266431 -0.6597379981 +2473 53.1768926078 -0.6611973038 +2474 53.1714729387 -0.6620681955 +2475 53.1660306441 -0.6623471645 +2476 53.1605890328 -0.6620332407 +2477 53.1551714022 -0.6611279923 +2478 53.1498009378 -0.6596355158 +2479 53.144500615 -0.6575624144 +2480 53.1392931008 -0.6549177659 +2481 53.134200657 -0.651713081 +2482 53.129245046 -0.6479622505 +2483 53.124447438 -0.6436814828 +2484 53.1198283214 -0.6388892324 +2485 53.1154074157 -0.6336061185 +2486 53.1112035887 -0.6278548351 +2487 53.1072347761 -0.6216600529 +2488 53.1035179065 -0.6150483124 +2489 53.1000688292 -0.6080479107 +2490 53.0969022484 -0.6006887801 +2491 53.0940316606 -0.5930023609 +2492 53.0914692984 -0.5850214681 +2493 53.0892260788 -0.5767801523 +2494 53.0873115574 -0.5683135565 +2495 53.0857338887 -0.5596577674 +2496 53.0844997914 -0.5508496647 +2497 53.0836145207 -0.5419267654 +2498 53.0830818461 -0.5329270671 +2499 53.0829040355 -0.5238888889 +2500 53.0830818461 -0.5148507107 +2501 53.0836145207 -0.5058510124 +2502 53.0844997914 -0.4969281131 +2503 53.0857338887 -0.4881200103 +2504 53.0873115574 -0.4794642213 +2505 53.0892260788 -0.4709976254 +2506 53.0914692984 -0.4627563097 +2507 53.0940316606 -0.4547754169 +2508 53.0969022484 -0.4470889977 +2509 53.1000688292 -0.4397298671 +2510 53.1035179065 -0.4327294654 +2511 53.1072347761 -0.4261177249 +2512 53.1112035887 -0.4199229426 +2513 53.1154074157 -0.4141716593 +2514 53.1198283214 -0.4088885453 +2515 53.124447438 -0.4040962949 +2516 53.129245046 -0.3998155273 +2517 53.134200657 -0.3960646967 +2518 53.1392931008 -0.3928600119 +2519 53.144500615 -0.3902153634 +2520 53.1498009378 -0.3881422619 +2521 53.1551714022 -0.3866497854 +2522 53.1605890328 -0.3857445371 +2523 53.1660306441 -0.3854306133 +2524 53.1714729387 -0.3857095823 +2525 53.1768926078 -0.386580474 +2526 53.182266431 -0.3880397797 +2527 53.1875713753 -0.3900814638 +2528 53.1927846947 -0.392696986 +2529 53.197884028 -0.395875334 +2530 53.202847495 -0.3996030676 +2531 53.2076537911 -0.4038643737 +2532 53.2122822792 -0.4086411306 +2533 53.2167130794 -0.4139129844 +2534 53.2209271548 -0.4196574336 +2535 53.2249063941 -0.4258499247 +2536 53.2286336905 -0.432463956 +2537 53.2320930161 -0.4394711916 +2538 53.2352694915 -0.4468415821 +2539 53.2381494508 -0.4545434945 +2540 53.2407205011 -0.4625438488 +2541 53.2429715769 -0.4708082614 +2542 53.2448929879 -0.4793011942 +2543 53.2464764618 -0.4879861096 +2544 53.2477151807 -0.4968256299 +2545 53.2486038102 -0.5057817003 +2546 53.2491385233 -0.5148157555 +2547 53.2493170173 -0.5238888889 +2548 53.2286111111 -0.7233333333 +2549 53.0220944444 -0.8306333333 +2550 52.9321694444 -0.3564722222 +2551 53.1383611111 -0.247825 +2552 53.2286111111 -0.7233333333 +2553 54.2261111111 -5.77 +2554 54.2569444444 -5.7883333333 +2555 54.2572222222 -5.8361111111 +2556 54.2552055556 -5.8353861111 +2557 54.2502138889 -5.8287416667 +2558 54.2466888889 -5.8250583333 +2559 54.2453583333 -5.8255055556 +2560 54.2444444444 -5.8277777778 +2561 54.2211111111 -5.8438888889 +2562 54.2155555556 -5.7927777778 +2563 54.2261111111 -5.77 +2564 55.0588888889 -5.0858333333 +2565 55.0383333333 -5.1525 +2566 54.97 -5.2027777778 +2567 54.6375 -4.8977777778 +2568 54.6541666667 -4.7813888889 +2569 54.6686111111 -4.8422222222 +2570 54.7041666667 -4.8941666667 +2571 54.7613888889 -4.9408333333 +2572 54.8313888889 -4.9480555556 +2573 54.8688888889 -4.9011111111 +2574 54.8713888889 -4.8594444444 +2575 54.85 -4.8294444444 +2576 54.8355555556 -4.8275 +2577 54.7805555556 -4.6436111111 +2578 54.9333333333 -4.7955555556 +2579 54.9333333333 -4.9666666667 +2580 55.0588888889 -5.0858333333 +2581 55.0588888889 -5.0858333333 +2582 54.9333333333 -4.9666666667 +2583 54.9333333333 -4.7955555556 +2584 55.0483333333 -4.9027777778 +2585 55.0588888889 -5.0858333333 +2586 54.9579361819 -4.9644444444 +2587 54.9577680078 -4.9673177437 +2588 54.9572703748 -4.9700733403 +2589 54.9564636675 -4.9725983613 +2590 54.9553809299 -4.9747893947 +2591 54.9540665095 -4.9765567285 +2592 54.9525742383 -4.9778280257 +2593 54.9509652263 -4.9785512828 +2594 54.9493053564 -4.9786969516 +2595 54.9476625859 -4.9782591389 +2596 54.9461041639 -4.9772558366 +2597 54.9446938793 -4.9757281738 +2598 54.9434894509 -4.9737387244 +2599 54.942540168 -4.9713689403 +2600 54.9418848754 -4.968715816 +2601 54.9415503861 -4.9658879218 +2602 54.9415503861 -4.963000967 +2603 54.9418848754 -4.9601730729 +2604 54.942540168 -4.9575199486 +2605 54.9434894509 -4.9551501645 +2606 54.9446938793 -4.9531607151 +2607 54.9461041639 -4.9516330523 +2608 54.9476625859 -4.95062975 +2609 54.9493053564 -4.9501919373 +2610 54.9509652263 -4.9503376061 +2611 54.9525742383 -4.9510608631 +2612 54.9540665095 -4.9523321604 +2613 54.9553809299 -4.9540994942 +2614 54.9564636675 -4.9562905276 +2615 54.9572703748 -4.9588155486 +2616 54.9577680078 -4.9615711452 +2617 54.9579361819 -4.9644444444 +2618 54.8613888889 -4.9105555556 +2619 54.8313888889 -4.9480555556 +2620 54.8138888889 -4.9461111111 +2621 54.85 -4.8294444444 +2622 54.8608333333 -4.8447222222 +2623 54.8613888889 -4.9105555556 +2624 54.8688888889 -4.9011111111 +2625 54.8313888889 -4.9480555556 +2626 54.7613888889 -4.9408333333 +2627 54.7041666667 -4.8941666667 +2628 54.6686111111 -4.8422222222 +2629 54.6541666667 -4.7813888889 +2630 54.6805555556 -4.5952777778 +2631 54.7177777778 -4.5833333333 +2632 54.7805555556 -4.6436111111 +2633 54.8355555556 -4.8275 +2634 54.85 -4.8294444444 +2635 54.8713888889 -4.8594444444 +2636 54.8688888889 -4.9011111111 +2637 54.7797222222 -4.0636111111 +2638 54.5936111111 -4.2538888889 +2639 54.5541666667 -4.2280555556 +2640 54.5505555556 -3.9555555556 +2641 54.6333333333 -3.8016666667 +2642 54.7861111111 -3.9416666667 +2643 54.805 -3.9513888889 +2644 54.8077777778 -4.0111111111 +2645 54.7955555556 -4.0372222222 +2646 54.7797222222 -4.0636111111 +2647 54.3491666667 -3.4630555556 +2648 54.4794444444 -3.645 +2649 54.3991666667 -3.8213888889 +2650 54.3902456908 -3.8264346983 +2651 54.381210064 -3.8308435947 +2652 54.3720838636 -3.8346650828 +2653 54.3628800713 -3.8378941188 +2654 54.353611771 -3.8405265112 +2655 54.3442921289 -3.8425589244 +2656 54.3349343758 -3.8439888809 +2657 54.3255517871 -3.8448147631 +2658 54.3161576648 -3.8450358126 +2659 54.306765318 -3.8446521295 +2660 54.2973880444 -3.8436646694 +2661 54.2880391114 -3.8420752404 +2662 54.2787317371 -3.8398864974 +2663 54.2694790723 -3.8371019368 +2664 54.2602941817 -3.8337258888 +2665 54.2511900257 -3.8297635095 +2666 54.2421794422 -3.8252207712 +2667 54.233275129 -3.8201044522 +2668 54.2244896262 -3.8144221249 +2669 54.2158352985 -3.8081821439 +2670 54.2073243185 -3.801393632 +2671 54.1989686499 -3.7940664656 +2672 54.1907800309 -3.7862112598 +2673 54.1827699581 -3.7778393517 +2674 54.1749496712 -3.7689627833 +2675 54.1673301372 -3.7595942835 +2676 54.1599220357 -3.7497472491 +2677 54.1527357444 -3.7394357252 +2678 54.1457813251 -3.7286743851 +2679 54.1390685101 -3.7174785086 +2680 54.1326066888 -3.7058639609 +2681 54.1264048954 -3.6938471693 +2682 54.1204717968 -3.6814451008 +2683 54.1148156806 -3.6686752382 +2684 54.1094444444 -3.6555555556 +2685 54.2836111111 -3.4563888889 +2686 54.2834617223 -3.4506623994 +2687 54.2836739162 -3.4449398451 +2688 54.2842226211 -3.4392829629 +2689 54.2851022495 -3.433749363 +2690 54.2863038428 -3.428395409 +2691 54.2878151632 -3.4232756474 +2692 54.2896208163 -3.4184422552 +2693 54.291702408 -3.4139445105 +2694 54.2940387298 -3.4098282922 +2695 54.2966059743 -3.4061356127 +2696 54.2993779763 -3.4029041892 +2697 54.3023264784 -3.4001670583 +2698 54.3054214177 -3.397952236 +2699 54.3086312313 -3.396282429 +2700 54.3119231776 -3.3951747988 +2701 54.3152636691 -3.3946407821 +2702 54.318618615 -3.3946859681 +2703 54.3219537687 -3.3953100364 +2704 54.3252350775 -3.3965067544 +2705 54.3284290303 -3.3982640352 +2706 54.3315030008 -3.4005640558 +2707 54.334425581 -3.4033834341 +2708 54.3371669033 -3.4066934642 +2709 54.339698947 -3.410460406 +2710 54.3419958252 -3.4146458278 +2711 54.3440340516 -3.4192069976 +2712 54.3457927812 -3.4240973199 +2713 54.3472540251 -3.4292668128 +2714 54.3484028352 -3.4346626206 +2715 54.3492274587 -3.4402295569 +2716 54.3497194586 -3.4459106726 +2717 54.3498738009 -3.4516478419 +2718 54.3496889063 -3.4573823616 +2719 54.3491666667 -3.4630555556 +2720 54.3202777778 -3.845 +2721 54.3211111111 -3.9872222222 +2722 54.3107175685 -3.9871594946 +2723 54.3003308501 -3.9864927438 +2724 54.2899613462 -3.985272219 +2725 54.2796191549 -3.9834995252 +2726 54.26931434 -3.9811768014 +2727 54.2590569217 -3.9783067165 +2728 54.2488568664 -3.9748924651 +2729 54.2387240779 -3.9709377632 +2730 54.2286683871 -3.9664468432 +2731 54.2186995434 -3.9614244476 +2732 54.2088272049 -3.955875824 +2733 54.1990609292 -3.9498067176 +2734 54.189410165 -3.9432233654 +2735 54.1798842425 -3.936132488 +2736 54.1704923649 -3.9285412827 +2737 54.1612435998 -3.9204574148 +2738 54.1521468707 -3.9118890095 +2739 54.1432109488 -3.902844643 +2740 54.1344444444 -3.8933333333 +2741 54.1802777778 -3.775 +2742 54.1880869067 -3.7834591208 +2743 54.1960923758 -3.7913702592 +2744 54.2042637884 -3.7987730162 +2745 54.2125900125 -3.8056570042 +2746 54.2210596989 -3.8120125251 +2747 54.2296612956 -3.8178305841 +2748 54.2383830637 -3.8231029043 +2749 54.2472130929 -3.827821939 +2750 54.2561393174 -3.831980884 +2751 54.2651495321 -3.8355736883 +2752 54.2742314093 -3.8385950649 +2753 54.2833725151 -3.8410404991 +2754 54.2925603262 -3.8429062576 +2755 54.3017822471 -3.8441893949 +2756 54.3110256271 -3.8448877597 +2757 54.3202777778 -3.845 +2758 54.3211111111 -3.9872222222 +2759 54.2369444444 -4.1736111111 +2760 54.2263311513 -4.1699727629 +2761 54.2157666889 -4.1659452033 +2762 54.2052619799 -4.1614866885 +2763 54.1948230752 -4.1566001131 +2764 54.1844559832 -4.1512886114 +2765 54.1741666667 -4.1455555556 +2766 54.1344444444 -3.8933333333 +2767 54.1432260183 -3.9028029361 +2768 54.1521611714 -3.9118465154 +2769 54.1612571176 -3.920414174 +2770 54.1705050866 -3.9284973363 +2771 54.1798961556 -3.936087878 +2772 54.1894212578 -3.9431781344 +2773 54.1990711908 -3.949760909 +2774 54.208836625 -3.9558294816 +2775 54.2187081128 -3.961377616 +2776 54.2286760972 -3.9663995673 +2777 54.238730921 -3.9708900887 +2778 54.2488628357 -3.9748444377 +2779 54.2590620111 -3.9782583827 +2780 54.2693185444 -3.981128208 +2781 54.27962247 -3.9834507192 +2782 54.2899637685 -3.9852232477 +2783 54.300332377 -3.9864436549 +2784 54.3107181984 -3.9871103357 +2785 54.3211111111 -3.9872222222 +2786 54.6366666667 -2.3463888889 +2787 54.5905555556 -2.4052777778 +2788 54.5619444444 -2.4266666667 +2789 54.5338888889 -2.3691666667 +2790 54.5322222222 -2.3452777778 +2791 54.5755555556 -2.2625 +2792 54.6313888889 -2.2338888889 +2793 54.6488888889 -2.2458333333 +2794 54.6366666667 -2.3463888889 +2795 54.4738888889 -1.8663888889 +2796 54.4555555556 -1.8972222222 +2797 54.4180555556 -1.8663888889 +2798 54.4130555556 -1.8344444444 +2799 54.4202777778 -1.8052777778 +2800 54.4488888889 -1.7816666667 +2801 54.4638888889 -1.8225 +2802 54.4738888889 -1.8663888889 +2803 54.0348818885 -1.0169444444 +2804 54.0347136897 -1.0197537238 +2805 54.0342159834 -1.0224479252 +2806 54.033409157 -1.0249166926 +2807 54.0323262586 -1.027058919 +2808 54.0310116417 -1.0287868913 +2809 54.0295191457 -1.0300298828 +2810 54.0279098892 -1.0307370464 +2811 54.0262497647 -1.0308794896 +2812 54.0246067401 -1.0304514472 +2813 54.023048075 -1.0294705074 +2814 54.0216375685 -1.0279768809 +2815 54.0204329494 -1.0260317464 +2816 54.0194835154 -1.0237147413 +2817 54.018828118 -1.0211207007 +2818 54.018493575 -1.0183557787 +2819 54.018493575 -1.0155331101 +2820 54.018828118 -1.0127681882 +2821 54.0194835154 -1.0101741476 +2822 54.0204329494 -1.0078571425 +2823 54.0216375685 -1.005912008 +2824 54.023048075 -1.0044183814 +2825 54.0246067401 -1.0034374417 +2826 54.0262497647 -1.0030093993 +2827 54.0279098892 -1.0031518424 +2828 54.0295191457 -1.0038590061 +2829 54.0310116417 -1.0051019976 +2830 54.0323262586 -1.0068299699 +2831 54.033409157 -1.0089721963 +2832 54.0342159834 -1.0114409637 +2833 54.0347136897 -1.0141351651 +2834 54.0348818885 -1.0169444444 +2835 54.9666666667 -0.3833333333 +2836 54.7625 -0.1547222222 +2837 54.7625 -0.0018650794 +2838 54.7625 0.1509920635 +2839 54.7625 0.3038492063 +2840 54.7625 0.4567063492 +2841 54.7625 0.6095634921 +2842 54.7625 0.7624206349 +2843 54.7625 0.9152777778 +2844 55.0666666667 1.35 +2845 55.4166666667 1.0 +2846 54.9666666667 -0.3833333333 +2847 54.3648293837 -1.8569444444 +2848 54.3646525232 -1.8615629685 +2849 54.3641249725 -1.8661023509 +2850 54.3632557713 -1.8704848124 +2851 54.3620598126 -1.874635274 +2852 54.3605575869 -1.8784826481 +2853 54.3587748295 -1.8819610599 +2854 54.3567420778 -1.8850109775 +2855 54.3544941467 -1.8875802316 +2856 54.3520695308 -1.8896249068 +2857 54.3495097429 -1.8911100904 +2858 54.3468586027 -1.8920104643 +2859 54.344161485 -1.8923107321 +2860 54.3414645427 -1.8920058734 +2861 54.3388139166 -1.8911012215 +2862 54.3362549466 -1.8896123644 +2863 54.3338313964 -1.8875648703 +2864 54.3315847065 -1.8849938442 +2865 54.3295532866 -1.8819433222 +2866 54.3277718611 -1.8784655147 +2867 54.3262708765 -1.8746199127 +2868 54.3250759836 -1.8704722699 +2869 54.3242076002 -1.8660934821 +2870 54.3236805636 -1.8615583776 +2871 54.3235038785 -1.8569444444 +2872 54.3236805636 -1.8523305113 +2873 54.3242076002 -1.8477954068 +2874 54.3250759836 -1.8434166189 +2875 54.3262708765 -1.8392689762 +2876 54.3277718611 -1.8354233741 +2877 54.3295532866 -1.8319455667 +2878 54.3315847065 -1.8288950447 +2879 54.3338313964 -1.8263240186 +2880 54.3362549466 -1.8242765245 +2881 54.3388139166 -1.8227876674 +2882 54.3414645427 -1.8218830155 +2883 54.344161485 -1.8215781568 +2884 54.3468586027 -1.8218784246 +2885 54.3495097429 -1.8227787985 +2886 54.3520695308 -1.8242639821 +2887 54.3544941467 -1.8263086573 +2888 54.3567420778 -1.8288779114 +2889 54.3587748295 -1.831927829 +2890 54.3605575869 -1.8354062408 +2891 54.3620598126 -1.8392536149 +2892 54.3632557713 -1.8434040765 +2893 54.3641249725 -1.847786538 +2894 54.3646525232 -1.8523259204 +2895 54.3648293837 -1.8569444444 +2896 55.1880555556 -6.9741666667 +2897 55.1688888889 -6.9425 +2898 55.1694444444 -6.8661111111 +2899 55.1852777778 -6.83 +2900 55.2147222222 -6.8591666667 +2901 55.2186111111 -6.9063888889 +2902 55.1880555556 -6.9741666667 +2903 55.1566124562 -2.1686111111 +2904 55.1564391851 -2.1719724508 +2905 55.1559249452 -2.1752256692 +2906 55.1550862772 -2.178266131 +2907 55.153950156 -2.1809960593 +2908 55.1525531206 -2.1833276853 +2909 55.1509400976 -2.1851860725 +2910 55.1491629534 -2.186511525 +2911 55.1472788247 -2.1872615013 +2912 55.1453482796 -2.1874119744 +2913 55.1434333695 -2.1869581941 +2914 55.1415956348 -2.1859148286 +2915 55.1398941272 -2.1843154823 +2916 55.1383835141 -2.182211607 +2917 55.1371123239 -2.1796708423 +2918 55.1361213894 -2.1767748386 +2919 55.1354425383 -2.1736166351 +2920 55.1350975733 -2.1702976739 +2921 55.1350975733 -2.1669245483 +2922 55.1354425383 -2.1636055872 +2923 55.1361213894 -2.1604473836 +2924 55.1371123239 -2.15755138 +2925 55.1383835141 -2.1550106152 +2926 55.1398941272 -2.1529067399 +2927 55.1415956348 -2.1513073936 +2928 55.1434333695 -2.1502640281 +2929 55.1453482796 -2.1498102478 +2930 55.1472788247 -2.149960721 +2931 55.1491629534 -2.1507106972 +2932 55.1509400976 -2.1520361497 +2933 55.1525531206 -2.1538945369 +2934 55.153950156 -2.1562261629 +2935 55.1550862772 -2.1589560912 +2936 55.1559249452 -2.161996553 +2937 55.1564391851 -2.1652497714 +2938 55.1566124562 -2.1686111111 +2939 55.2083333333 -5.65 +2940 55.1083333333 -5.7166666667 +2941 54.93 -5.4666666667 +2942 54.9916666667 -5.2616666667 +2943 55.1183333333 -5.1166666667 +2944 55.2083333333 -5.11 +2945 55.2083333333 -5.245 +2946 55.2083333333 -5.38 +2947 55.2083333333 -5.515 +2948 55.2083333333 -5.65 +2949 55.25 -2.8821305556 +2950 55.25 -2.9 +2951 55.15 -3.0 +2952 55.019925 -2.7480777778 +2953 55.25 -2.8821305556 +2954 55.25 -2.8821305556 +2955 55.019925 -2.7480777778 +2956 55.0 -2.7097222222 +2957 55.0 -2.4644444444 +2958 55.035 -2.2777777778 +2959 55.0713888889 -2.2880555556 +2960 55.0813888889 -2.2952777778 +2961 55.25 -2.6641666667 +2962 55.25 -2.8821305556 +2963 55.0702401658 -2.59065 +2964 55.0700649075 -2.5957932319 +2965 55.0695415973 -2.6008641309 +2966 55.0686775946 -2.6057913869 +2967 55.0674850495 -2.6105057207 +2968 55.0659807311 -2.614940863 +2969 55.06418579 -2.6190344894 +2970 55.0621254604 -2.6227290992 +2971 55.0598287028 -2.6259728243 +2972 55.0573277963 -2.6287201577 +2973 55.0546578824 -2.6309325909 +2974 55.0518564705 -2.6325791506 +2975 55.0489629096 -2.6336368295 +2976 55.0460178342 -2.6340909028 +2977 55.0430625935 -2.6339351282 +2978 55.0401386701 -2.6331718261 +2979 55.0372870984 -2.6318118396 +2980 55.0345478888 -2.6298743751 +2981 55.031959467 -2.6273867262 +2982 55.0295581366 -2.6243838853 +2983 55.0273775709 -2.6209080484 +2984 55.025448342 -2.6170080203 +2985 55.0237974946 -2.612738529 +2986 55.0224481674 -2.6081594582 +2987 55.0214192711 -2.6033350102 +2988 55.0207252243 -2.5983328083 +2989 55.0203757525 -2.5932229534 +2990 55.0203757525 -2.5880770466 +2991 55.0207252243 -2.5829671917 +2992 55.0214192711 -2.5779649898 +2993 55.0224481674 -2.5731405418 +2994 55.0237974946 -2.568561471 +2995 55.025448342 -2.5642919797 +2996 55.0273775709 -2.5603919516 +2997 55.0295581366 -2.5569161147 +2998 55.031959467 -2.5539132738 +2999 55.0345478888 -2.5514256249 +3000 55.0372870984 -2.5494881604 +3001 55.0401386701 -2.5481281739 +3002 55.0430625935 -2.5473648718 +3003 55.0460178342 -2.5472090972 +3004 55.0489629096 -2.5476631705 +3005 55.0518564705 -2.5487208494 +3006 55.0546578824 -2.5503674091 +3007 55.0573277963 -2.5525798423 +3008 55.0598287028 -2.5553271757 +3009 55.0621254604 -2.5585709008 +3010 55.06418579 -2.5622655106 +3011 55.0659807311 -2.566359137 +3012 55.0674850495 -2.5707942793 +3013 55.0686775946 -2.5755086131 +3014 55.0695415973 -2.5804358691 +3015 55.0700649075 -2.5855067681 +3016 55.0702401658 -2.59065 +3017 55.2383333333 -2.0441666667 +3018 55.2569444444 -2.2311111111 +3019 55.3158333333 -2.3875 +3020 55.2708333333 -2.4311111111 +3021 55.1816666667 -2.2197222222 +3022 55.2383333333 -2.0441666667 +3023 55.4072222222 -2.2319444444 +3024 55.37 -2.3358333333 +3025 55.3158333333 -2.3875 +3026 55.2569444444 -2.2311111111 +3027 55.2383333333 -2.0441666667 +3028 55.2886111111 -2.06 +3029 55.4072222222 -2.2319444444 +3030 55.0333333333 -1.0 +3031 55.0333333333 -0.6666666667 +3032 55.3333333333 -0.3833333333 +3033 55.3333333333 -1.1111111111 +3034 55.0333333333 -1.0 +3035 55.7333333333 -1.2619444444 +3036 55.3333333333 -1.1111111111 +3037 55.3333333333 -0.3833333333 +3038 55.0333333333 -0.6666666667 +3039 55.3333333333 0.2833333333 +3040 55.7333333333 0.1238888889 +3041 55.7333333333 -1.2619444444 +3042 55.8333333333 -1.3 +3043 55.0333333333 -1.0 +3044 55.0333333333 -0.6666666667 +3045 55.3333333333 0.2833333333 +3046 55.8333333333 0.0833333333 +3047 55.8333333333 -1.3 +3048 56.8287937778 -2.5163368333 +3049 56.6316858611 -2.7668234167 +3050 56.2213935 -2.8739837778 +3051 56.0226490556 -2.6626117778 +3052 55.6578733611 -2.7031990833 +3053 55.49769625 -2.5130380278 +3054 55.2341564444 -1.7079248333 +3055 55.2406800833 -1.683344 +3056 55.2693510278 -1.5759322778 +3057 55.32227475 -1.3351568333 +3058 55.3157079327 -1.3196354763 +3059 55.3088632909 -1.304490274 +3060 55.3017477663 -1.2897364284 +3061 55.2943685832 -1.2753887059 +3062 55.2867332297 -1.2614614361 +3063 55.2788494494 -1.2479684983 +3064 55.2707252331 -1.2349233067 +3065 55.2623688104 -1.2223387981 +3066 55.2537886408 -1.2102274184 +3067 55.2449934046 -1.1986011112 +3068 55.2359919941 -1.1874713062 +3069 55.2267935037 -1.1768489084 +3070 55.2174072208 -1.1667442882 +3071 55.2078426155 -1.1571672715 +3072 55.1981093312 -1.1481271314 +3073 55.1882171739 -1.13963258 +3074 55.1781761027 -1.1316917604 +3075 55.1679962188 -1.1243122408 +3076 55.1576877554 -1.1175010074 +3077 55.1472610668 -1.1112644597 +3078 55.1367266181 -1.1056084054 +3079 55.1260949743 -1.1005380561 +3080 55.1153767893 -1.096058024 +3081 55.1045827952 -1.0921723192 +3082 55.0937237913 -1.0888843473 +3083 55.0828106334 -1.0861969081 +3084 55.0718542222 -1.0841121944 +3085 55.0526792778 -1.0414236389 +3086 54.3935690833 1.3735272222 +3087 55.8078658611 2.0298775556 +3088 56.2561136389 0.6521053333 +3089 56.8287937778 -2.5163368333 +3090 56.1347222222 -4.7766666667 +3091 56.1183333333 -4.82 +3092 56.0963888889 -4.82 +3093 56.0777777778 -4.7944444444 +3094 56.0847222222 -4.7822222222 +3095 56.1347222222 -4.7766666667 +3096 56.4802777778 -2.8136111111 +3097 56.4605555556 -2.8080555556 +3098 56.4597222222 -2.6619444444 +3099 56.4991666667 -2.6694444444 +3100 56.4802777778 -2.8136111111 +3101 57.7391472222 0.4419305556 +3102 57.2462805556 -1.7715583333 +3103 56.7901638889 -1.5996 +3104 57.32785 0.8140888889 +3105 57.7391472222 0.4419305556 +3106 57.32785 0.8140888889 +3107 56.7901638889 -1.5996 +3108 56.8823361111 1.2068416667 +3109 57.32785 0.8140888889 +3110 56.8823361111 1.2068416667 +3111 56.7901638889 -1.5996 +3112 56.2971694444 -1.4184805556 +3113 56.8823361111 1.2068416667 +3114 56.8823361111 1.2068416667 +3115 56.2971694444 -1.4184805556 +3116 56.0857027778 -0.4851527778 +3117 56.0623555556 1.9031472222 +3118 56.8823361111 1.2068416667 +3119 57.5630555556 -7.8008333333 +3120 57.5556144002 -7.8147936092 +3121 57.5479228699 -7.8282732985 +3122 57.5399919141 -7.841261266 +3123 57.5318305591 -7.8537430548 +3124 57.5234480871 -7.8657048125 +3125 57.5148540252 -7.877133306 +3126 57.5060581345 -7.8880159355 +3127 57.4970703978 -7.8983407475 +3128 57.4879010084 -7.9080964477 +3129 57.4785603579 -7.9172724118 +3130 57.4690590239 -7.9258586962 +3131 57.4594077576 -7.9338460477 +3132 57.4496174713 -7.9412259119 +3133 57.4396992258 -7.9479904416 +3134 57.4296642173 -7.9541325028 +3135 57.4195237646 -7.9596456814 +3136 57.4092892961 -7.9645242879 +3137 57.3989723365 -7.9687633616 +3138 57.3885844937 -7.972358674 +3139 57.3781374455 -7.975306731 +3140 57.3676429262 -7.9776047746 +3141 57.3571127135 -7.9792507833 +3142 57.3465586152 -7.9802434722 +3143 57.3359924554 -7.9805822915 +3144 57.325426062 -7.980267425 +3145 57.3148712527 -7.979299787 +3146 57.3043398224 -7.9776810193 +3147 57.2938435297 -7.9754134861 +3148 57.283394084 -7.9725002697 +3149 57.2730031328 -7.9689451642 +3150 57.2626822485 -7.9647526688 +3151 57.2524429158 -7.959927981 +3152 57.2422965194 -7.9544769877 +3153 57.2322543314 -7.9484062576 +3154 57.222327499 -7.9417230308 +3155 57.2125270325 -7.9344352093 +3156 57.2028637936 -7.9265513463 +3157 57.1933484835 -7.9180806346 +3158 57.1839916314 -7.9090328952 +3159 57.1748035833 -7.8994185645 +3160 57.1657944914 -7.8892486813 +3161 57.1569743024 -7.8785348735 +3162 57.148352748 -7.8672893439 +3163 57.1399393337 -7.8555248557 +3164 57.1317433295 -7.8432547174 +3165 57.1237737598 -7.8304927676 +3166 57.116039394 -7.8172533586 +3167 57.1085487375 -7.8035513406 +3168 57.1013100226 -7.7894020448 +3169 57.0943312 -7.7748212661 +3170 57.0876199308 -7.7598252458 +3171 57.0811835783 -7.7444306541 +3172 57.0750292004 -7.7286545713 +3173 57.0691635427 -7.71251447 +3174 57.063593031 -7.696028196 +3175 57.058323765 -7.6792139495 +3176 57.0533615124 -7.6620902657 +3177 57.0487117023 -7.6446759953 +3178 57.0443794202 -7.6269902851 +3179 57.0403694026 -7.6090525576 +3180 57.0366860321 -7.5908824912 +3181 57.0333333333 -7.5725 +3182 57.1761111111 -7.5252777778 +3183 57.1822222222 -7.3813888889 +3184 57.3630555556 -7.3544444444 +3185 57.39 -7.3758333333 +3186 57.3813888889 -7.4252777778 +3187 57.5630555556 -7.8008333333 +3188 57.0333333333 -7.5725 +3189 57.0366888943 -7.5908806376 +3190 57.0403722297 -7.6090505306 +3191 57.0443822091 -7.6269880869 +3192 57.0487144499 -7.6446736282 +3193 57.0533642157 -7.6620877322 +3194 57.058326421 -7.6792112525 +3195 57.0635956367 -7.6960253382 +3196 57.0691660953 -7.7125114546 +3197 57.075031697 -7.7286514014 +3198 57.0811860162 -7.7444273331 +3199 57.0876223072 -7.7598217773 +3200 57.0943335124 -7.7748176538 +3201 57.1013122683 -7.7893982926 +3202 57.1085509141 -7.8035474526 +3203 57.1160414991 -7.817249339 +3204 57.123775791 -7.8304886206 +3205 57.1317452846 -7.8432504477 +3206 57.1399412104 -7.8555204677 +3207 57.1483545443 -7.8672848425 +3208 57.1569760164 -7.8785302635 +3209 57.165796121 -7.8892439677 +3210 57.1748051268 -7.8994137525 +3211 57.1839930869 -7.9090279901 +3212 57.1933498495 -7.9180756416 +3213 57.2028650685 -7.9265462709 +3214 57.2125282149 -7.9344300571 +3215 57.2223285875 -7.9417178074 +3216 57.2322553248 -7.9484009688 +3217 57.2422974166 -7.9544716393 +3218 57.2524437158 -7.9599225788 +3219 57.2626829503 -7.964747219 +3220 57.2730037357 -7.9689396726 +3221 57.2833945872 -7.9724947425 +3222 57.2938439326 -7.9754079293 +3223 57.3043401245 -7.9776754391 +3224 57.3148714537 -7.9792941897 +3225 57.3254261616 -7.9802618168 +3226 57.3359924536 -7.9805766787 +3227 57.3465585118 -7.980237861 +3228 57.3571125087 -7.9792451801 +3229 57.3676426201 -7.9775991856 +3230 57.3781370385 -7.9753011625 +3231 57.3885839862 -7.9723531322 +3232 57.3989717291 -7.9687578529 +3233 57.4092885894 -7.9645188184 +3234 57.4195229594 -7.9596402574 +3235 57.4296633144 -7.9541271304 +3236 57.4396982262 -7.9479851269 +3237 57.4496163762 -7.941220661 +3238 57.4594065681 -7.9338408665 +3239 57.4690577413 -7.9258535907 +3240 57.4785589837 -7.9172673878 +3241 57.4878995441 -7.9080915109 +3242 57.497068845 -7.8983359036 +3243 57.5060564949 -7.88801119 +3244 57.5148523008 -7.8771286645 +3245 57.5234462797 -7.8657002803 +3246 57.5318286708 -7.8537386371 +3247 57.5399899469 -7.8412569678 +3248 57.547920826 -7.8282691249 +3249 57.555612282 -7.814789565 +3250 57.5630555556 -7.8008333333 +3251 57.7065416667 -8.1016944444 +3252 57.7539222222 -8.5088277778 +3253 57.8003527778 -9.3442027778 +3254 57.2840638889 -9.3463777778 +3255 56.9536111111 -7.5988888889 +3256 57.0333333333 -7.5725 +3257 57.8003527778 -9.3442027778 +3258 57.7539222222 -8.5088277778 +3259 57.7065416667 -8.1016944444 +3260 57.5630555556 -7.8008333333 +3261 57.5700722445 -7.786893946 +3262 57.5768067724 -7.772476361 +3263 57.5832844235 -7.7576539429 +3264 57.5894982237 -7.7424424392 +3265 57.5954414793 -7.7268580417 +3266 57.601107785 -7.7109173688 +3267 57.6064910309 -7.6946374473 +3268 57.6115854099 -7.6780356935 +3269 57.6163854238 -7.6611298942 +3270 57.6208858901 -7.6439381861 +3271 57.625081948 -7.6264790362 +3272 57.6289690637 -7.6087712203 +3273 57.6325430357 -7.590833802 +3274 57.6358 -7.5726861111 +3275 57.865 -7.7588888889 +3276 57.9442055556 -8.1755777778 +3277 57.8003527778 -9.3442027778 +3278 57.2840638889 -9.3463777778 +3279 56.9342638889 -9.0 +3280 56.7172722222 -7.6666666667 +3281 56.9669944444 -7.6666666667 +3282 57.2840638889 -9.3463777778 +3283 58.4831388889 -9.6834222222 +3284 58.0775 -8.8980555556 +3285 57.9030305556 -8.5201277778 +3286 57.9442055556 -8.1755777778 +3287 57.865 -7.7588888889 +3288 57.6910777778 -7.6173694444 +3289 57.8231472222 -7.25 +3290 58.4831388889 -8.8276361111 +3291 58.4831388889 -8.9987933333 +3292 58.4831388889 -9.1699505556 +3293 58.4831388889 -9.3411077778 +3294 58.4831388889 -9.512265 +3295 58.4831388889 -9.6834222222 +3296 59.5 -10.0 +3297 58.4831388889 -10.0 +3298 58.4831388889 -9.8325194444 +3299 58.4831388889 -9.6650388889 +3300 58.4831388889 -9.4975583333 +3301 58.4831388889 -9.3300777778 +3302 58.4831388889 -9.1625972222 +3303 58.4831388889 -8.9951166667 +3304 58.4831388889 -8.8276361111 +3305 57.8231472222 -7.25 +3306 58.4235972222 -7.1430638889 +3307 58.7873638889 -7.8206222222 +3308 59.5 -10.0 +3309 58.4831388889 -10.0 +3310 57.5501444444 -10.0 +3311 57.2840638889 -9.3463777778 +3312 57.8003527778 -9.3442027778 +3313 57.9030305556 -8.5201277778 +3314 58.0775 -8.8980555556 +3315 58.4831388889 -9.6834222222 +3316 58.4831388889 -9.8417111111 +3317 58.4831388889 -10.0 +3318 57.5501444444 -10.0 +3319 57.25 -10.0 +3320 56.9342638889 -9.0 +3321 57.2840638889 -9.3463777778 +3322 57.5501444444 -10.0 +3323 57.25 -10.0 +3324 56.7633694444 -10.0 +3325 56.5898861111 -8.6245138889 +3326 56.5859805556 -7.7185305556 +3327 56.7172722222 -7.6666666667 +3328 56.9342638889 -9.0 +3329 57.25 -10.0 +3330 56.7633694444 -10.0 +3331 56.5896416667 -10.0 +3332 56.0608027778 -7.7374527778 +3333 56.5859805556 -7.7185305556 +3334 56.5898861111 -8.6245138889 +3335 56.7633694444 -10.0 +3336 56.5896416667 -10.0 +3337 56.4417388889 -10.0 +3338 55.8519 -8.0585555556 +3339 55.8519 -8.0 +3340 56.0608027778 -7.7374527778 +3341 56.5896416667 -10.0 +3342 56.4417388889 -10.0 +3343 56.0917611111 -10.0 +3344 56.0762722222 -8.7777972222 +3345 56.4417388889 -10.0 +3346 56.0917611111 -10.0 +3347 55.7545083333 -10.0 +3348 55.6666666667 -9.4188888889 +3349 55.6666666667 -9.2612345679 +3350 55.6666666667 -9.1035802469 +3351 55.6666666667 -8.9459259259 +3352 55.6666666667 -8.7882716049 +3353 55.6666666667 -8.630617284 +3354 55.6666666667 -8.472962963 +3355 55.6666666667 -8.315308642 +3356 55.6666666667 -8.157654321 +3357 55.6666666667 -8.0 +3358 55.8519 -8.0 +3359 55.8519 -8.0585555556 +3360 56.0762722222 -8.7777972222 +3361 56.0917611111 -10.0 +3362 56.53005 -11.7529138889 +3363 55.8977805556 -11.0 +3364 55.7545083333 -10.0 +3365 56.0917611111 -10.0 +3366 56.53005 -11.7529138889 +3367 57.0 -12.0 +3368 56.7324472222 -12.0 +3369 56.53005 -11.7529138889 +3370 56.0917611111 -10.0 +3371 56.4417388889 -10.0 +3372 57.0 -12.0 +3373 57.3568694444 -12.0 +3374 57.0 -12.0 +3375 56.4417388889 -10.0 +3376 56.7633694444 -10.0 +3377 56.8439194444 -10.6883611111 +3378 57.3568694444 -12.0 +3379 57.3568694444 -12.0 +3380 56.8439194444 -10.6883611111 +3381 56.7633694444 -10.0 +3382 57.25 -10.0 +3383 57.3568694444 -12.0 +3384 58.0264222222 -12.0 +3385 57.3568694444 -12.0 +3386 57.25 -10.0 +3387 57.5501444444 -10.0 +3388 58.0264222222 -12.0 +3389 58.7539083333 -12.0 +3390 58.0264222222 -12.0 +3391 57.5501444444 -10.0 +3392 58.4831388889 -10.0 +3393 58.7539083333 -12.0 +3394 59.5 -12.0 +3395 58.7539083333 -12.0 +3396 58.4831388889 -10.0 +3397 59.5 -10.0 +3398 59.5 -10.1666666667 +3399 59.5 -10.3333333333 +3400 59.5 -10.5 +3401 59.5 -10.6666666667 +3402 59.5 -10.8333333333 +3403 59.5 -11.0 +3404 59.5 -11.1666666667 +3405 59.5 -11.3333333333 +3406 59.5 -11.5 +3407 59.5 -11.6666666667 +3408 59.5 -11.8333333333 +3409 59.5 -12.0 +3410 59.0 -13.0 +3411 58.8765361111 -13.0 +3412 58.7539083333 -12.0 +3413 59.5 -12.0 +3414 59.0 -13.0 +3415 58.8765361111 -13.0 +3416 58.2481972222 -13.0 +3417 58.0264222222 -12.0 +3418 58.7539083333 -12.0 +3419 58.8765361111 -13.0 +3420 58.2481972222 -13.0 +3421 57.5239055556 -13.0 +3422 57.3568694444 -12.0 +3423 58.0264222222 -12.0 +3424 58.2481972222 -13.0 +3425 57.5239055556 -13.0 +3426 56.7324472222 -12.0 +3427 57.3568694444 -12.0 +3428 57.5239055556 -13.0 +3429 57.6358 -7.5726861111 +3430 57.6325005233 -7.5908058302 +3431 57.6289270654 -7.6087406711 +3432 57.6250405088 -7.6264459435 +3433 57.6208450543 -7.6439025864 +3434 57.6163452351 -7.6610918269 +3435 57.6115459113 -7.6779952008 +3436 57.6064522647 -7.6945945737 +3437 57.6010697925 -7.7108721616 +3438 57.5954043011 -7.7268105508 +3439 57.5894618995 -7.7423927169 +3440 57.583248992 -7.7576020438 +3441 57.5767722714 -7.7724223421 +3442 57.5700387107 -7.7868378667 +3443 57.5630555556 -7.8008333333 +3444 57.3813888889 -7.4252777778 +3445 57.39 -7.3758333333 +3446 57.6358 -7.5726861111 +3447 57.6047222222 -4.0130555556 +3448 57.5927777778 -4.0605555556 +3449 57.5822222222 -4.0772222222 +3450 57.5777777778 -4.0491666667 +3451 57.5802777778 -4.0244444444 +3452 57.6047222222 -4.0130555556 +3453 57.8733333333 -3.5083333333 +3454 57.8733333333 -3.5 +3455 58.05 -3.5 +3456 58.1166666667 -3.6166666667 +3457 58.0566666667 -3.7433333333 +3458 57.86 -4.1366666667 +3459 57.75 -4.0483333333 +3460 57.75 -3.9166666667 +3461 57.8483333333 -3.775 +3462 57.8733333333 -3.5083333333 +3463 57.6241666667 -7.3030555556 +3464 57.5513888889 -7.5047222222 +3465 57.4402777778 -7.4158333333 +3466 57.5286111111 -7.1819444444 +3467 57.6241666667 -7.3030555556 +3468 57.3666666667 -5.8241666667 +3469 57.3676027778 -5.8226555556 +3470 57.3688666667 -5.8224527778 +3471 57.3721638889 -5.8234638889 +3472 57.373225 -5.8240722222 +3473 57.3749777778 -5.8225916667 +3474 57.3770833333 -5.8243083333 +3475 57.37795 -5.8253972222 +3476 57.3815166667 -5.8264361111 +3477 57.3837111111 -5.8251666667 +3478 57.3867444444 -5.8259833333 +3479 57.3879833333 -5.8266111111 +3480 57.3894583333 -5.8284305556 +3481 57.39085 -5.829925 +3482 57.3919722222 -5.8288083333 +3483 57.3913055556 -5.8265416667 +3484 57.3913027778 -5.8242083333 +3485 57.3894555556 -5.8240833333 +3486 57.3876138889 -5.8210777778 +3487 57.3894972222 -5.818275 +3488 57.3915472222 -5.8188222222 +3489 57.3936527778 -5.8205416667 +3490 57.3950833333 -5.8208555556 +3491 57.3980166667 -5.8189972222 +3492 57.4014888889 -5.8183916667 +3493 57.4009194444 -5.8152333333 +3494 57.399725 -5.8142611111 +3495 57.3978333333 -5.8131638889 +3496 57.3950944444 -5.8121638889 +3497 57.3954944444 -5.8105222222 +3498 57.393875 -5.8097055556 +3499 57.3940694444 -5.8080416667 +3500 57.3918833333 -5.8062666667 +3501 57.391125 -5.803125 +3502 57.3927444444 -5.803125 +3503 57.3953583333 -5.8058944444 +3504 57.3961916667 -5.8079805556 +3505 57.3991361111 -5.8087861111 +3506 57.3990277778 -5.8064416667 +3507 57.4000444444 -5.8055472222 +3508 57.4014166667 -5.8076888889 +3509 57.4054472222 -5.808275 +3510 57.4064611111 -5.8103805556 +3511 57.4072611111 -5.8136277778 +3512 57.4105222222 -5.8158 +3513 57.4119611111 -5.8187833333 +3514 57.4112722222 -5.8237111111 +3515 57.4131388889 -5.8244055556 +3516 57.4161222222 -5.8238833333 +3517 57.4179944444 -5.8244111111 +3518 57.4192694444 -5.8238777778 +3519 57.4224833333 -5.8217138889 +3520 57.42475 -5.8211166667 +3521 57.4276194444 -5.8184166667 +3522 57.4283805556 -5.8169944444 +3523 57.4308611111 -5.8152527778 +3524 57.4322222222 -5.8148944444 +3525 57.4333583333 -5.8130111111 +3526 57.4341694444 -5.8099277778 +3527 57.4371055556 -5.8050638889 +3528 57.4399527778 -5.8060277778 +3529 57.4409972222 -5.8101388889 +3530 57.4416805556 -5.8113777778 +3531 57.4432361111 -5.816375 +3532 57.4412805556 -5.8245111111 +3533 57.4408555556 -5.8296361111 +3534 57.4404638889 -5.8365972222 +3535 57.4406305556 -5.83995 +3536 57.4402305556 -5.8442444444 +3537 57.4408694444 -5.8498166667 +3538 57.4417055556 -5.8519055556 +3539 57.444825 -5.8557361111 +3540 57.4479861111 -5.8582361111 +3541 57.4515361111 -5.8597777778 +3542 57.4545638889 -5.8607666667 +3543 57.457825 -5.8599416667 +3544 57.4616833333 -5.8601833333 +3545 57.4643916667 -5.8628055556 +3546 57.4670611111 -5.8637527778 +3547 57.4687333333 -5.8619277778 +3548 57.4705277778 -5.8621166667 +3549 57.4691833333 -5.8678166667 +3550 57.4702722222 -5.8704361111 +3551 57.4751027778 -5.8712805556 +3552 57.4798944444 -5.8674472222 +3553 57.4849305556 -5.8674805556 +3554 57.4896611111 -5.86865 +3555 57.4921611111 -5.8662416667 +3556 57.4954944444 -5.8660944444 +3557 57.497675 -5.8653222222 +3558 57.5017416667 -5.8675888889 +3559 57.5071111111 -5.8654861111 +3560 57.5076055556 -5.8640333333 +3561 57.5101666667 -5.8626361111 +3562 57.514425 -5.8615805556 +3563 57.5167083333 -5.8604861111 +3564 57.520675 -5.8572277778 +3565 57.5229694444 -5.8556333333 +3566 57.5265583333 -5.8530027778 +3567 57.5312138889 -5.8536611111 +3568 57.5335555556 -5.853575 +3569 57.5392833333 -5.8515055556 +3570 57.54205 -5.8521333333 +3571 57.5439444444 -5.8519972222 +3572 57.5497638889 -5.8527805556 +3573 57.5524083333 -5.8457 +3574 57.5549638889 -5.8444638889 +3575 57.5582833333 -5.8476583333 +3576 57.5612222222 -5.8486388889 +3577 57.5626972222 -5.8474555556 +3578 57.56215 -5.8447194444 +3579 57.5595194444 -5.8395916667 +3580 57.5567916667 -5.8376305556 +3581 57.5591333333 -5.8345305556 +3582 57.5607555556 -5.8343666667 +3583 57.5638638889 -5.8356972222 +3584 57.5689083333 -5.8353916667 +3585 57.5702444444 -5.8387138889 +3586 57.5733666667 -5.8395444444 +3587 57.5764694444 -5.8410444444 +3588 57.5765416667 -5.8387083333 +3589 57.5774277778 -5.8361222222 +3590 57.5791666667 -5.8333333333 +3591 57.6333333333 -5.8333333333 +3592 57.6333333333 -5.9666666667 +3593 57.5833333333 -5.9666666667 +3594 57.5819638889 -5.9656777778 +3595 57.5796722222 -5.9642555556 +3596 57.5807944444 -5.960025 +3597 57.5793611111 -5.9598694444 +3598 57.5791222222 -5.9559944444 +3599 57.5780472222 -5.9558777778 +3600 57.5758694444 -5.9564777778 +3601 57.5734611111 -5.9558805556 +3602 57.5693166667 -5.9561 +3603 57.5685777778 -5.9538444444 +3604 57.5656111111 -5.9538555556 +3605 57.5646305556 -5.9564277778 +3606 57.562875 -5.9579111111 +3607 57.5613888889 -5.9565777778 +3608 57.5595527778 -5.9577166667 +3609 57.5574972222 -5.9601694444 +3610 57.5550638889 -5.9604083333 +3611 57.5524388889 -5.9609583333 +3612 57.5517277778 -5.9635583333 +3613 57.5493333333 -5.9653055556 +3614 57.546725 -5.9653555556 +3615 57.5441722222 -5.9635722222 +3616 57.5423444444 -5.9645444444 +3617 57.5413166667 -5.9657694444 +3618 57.5386861111 -5.9664888889 +3619 57.5371611111 -5.9691638889 +3620 57.5342111111 -5.968675 +3621 57.5318333333 -5.9699222222 +3622 57.5305 -5.9722833333 +3623 57.5282333333 -5.9700305556 +3624 57.5265611111 -5.9688472222 +3625 57.5249805556 -5.9705138889 +3626 57.5237527778 -5.9723861111 +3627 57.5226694444 -5.9724361111 +3628 57.5207194444 -5.9715555556 +3629 57.5185638889 -5.9743277778 +3630 57.5165833333 -5.9744472222 +3631 57.515375 -5.9756527778 +3632 57.51285 -5.9758777778 +3633 57.5109416667 -5.9765055556 +3634 57.5094305556 -5.9816888889 +3635 57.50885 -5.9858027778 +3636 57.5053083333 -5.9897583333 +3637 57.5034527778 -5.9887194444 +3638 57.5028861111 -5.9866527778 +3639 57.5006888889 -5.9850777778 +3640 57.4998388889 -5.9834805556 +3641 57.497325 -5.983375 +3642 57.495 -5.9801138889 +3643 57.4932611111 -5.9782555556 +3644 57.4913833333 -5.9807222222 +3645 57.4902027778 -5.9810944444 +3646 57.4882305556 -5.9808805556 +3647 57.485675 -5.9821027778 +3648 57.4845638889 -5.9831527778 +3649 57.4816833333 -5.9831722222 +3650 57.4796861111 -5.9837888889 +3651 57.4778055556 -5.9864222222 +3652 57.4762861111 -5.9860888889 +3653 57.4740027778 -5.987175 +3654 57.4706722222 -5.99015 +3655 57.468775 -5.9904444444 +3656 57.4651111111 -5.9925472222 +3657 57.4610611111 -5.9954416667 +3658 57.4583055556 -5.9973111111 +3659 57.4569805556 -5.9993361111 +3660 57.4550833333 -5.9996277778 +3661 57.45395 -6.0013388889 +3662 57.4519416667 -6.0022861111 +3663 57.4504444444 -6.004125 +3664 57.4505277778 -6.0071361111 +3665 57.4497472222 -6.0090527778 +3666 57.4480333333 -6.0092 +3667 57.4472277778 -6.0119472222 +3668 57.4445638889 -6.0136555556 +3669 57.4435527778 -6.02005 +3670 57.4414222222 -6.0248194444 +3671 57.4378361111 -6.0272611111 +3672 57.4345611111 -6.0312361111 +3673 57.4327416667 -6.0318694444 +3674 57.4279138889 -6.0310027778 +3675 57.4232166667 -6.0259861111 +3676 57.4188888889 -6.0235111111 +3677 57.4163277778 -6.0220611111 +3678 57.4116277778 -6.0200472222 +3679 57.4092083333 -6.0197805556 +3680 57.406625 -6.0189972222 +3681 57.4043666667 -6.01925 +3682 57.4007 -6.0186805556 +3683 57.3976777778 -6.0175166667 +3684 57.3952388889 -6.0179166667 +3685 57.3895638889 -6.0181277778 +3686 57.3851805556 -6.01465 +3687 57.3831666667 -6.0129305556 +3688 57.3794777778 -6.0101944444 +3689 57.3759333333 -6.0056472222 +3690 57.3738638889 -6.0029222222 +3691 57.3709527778 -6.0011083333 +3692 57.3695388889 -5.9974583333 +3693 57.3707888889 -5.9949305556 +3694 57.3704722222 -5.9935638889 +3695 57.3679805556 -5.9927944444 +3696 57.3666666667 -5.9930555556 +3697 57.3666666667 -5.8241666667 +3698 58.8673305556 -5.4496722222 +3699 58.7421972222 -5.9194527778 +3700 58.3221666667 -5.8786277778 +3701 58.2194277778 -5.3955861111 +3702 58.8673305556 -5.4496722222 +3703 59.2454388889 -3.9668944444 +3704 58.8673305556 -5.4496722222 +3705 58.2194277778 -5.3955861111 +3706 58.0700666667 -4.7129333333 +3707 59.1212277778 -3.552325 +3708 59.2454388889 -3.9668944444 +3709 59.1212277778 -3.552325 +3710 58.0700666667 -4.7129333333 +3711 57.8074444444 -3.5638888889 +3712 58.7817138889 -2.4555083333 +3713 59.1212277778 -3.552325 +3714 58.7817138889 -2.4555083333 +3715 57.8074444444 -3.5638888889 +3716 57.6666666667 -2.9724805556 +3717 57.6666666667 -2.8281583333 +3718 57.6666666667 -2.6838361111 +3719 57.6666666667 -2.5395138889 +3720 57.6666666667 -2.3951916667 +3721 57.6666666667 -2.2508694444 +3722 57.6666666667 -2.1065472222 +3723 58.6059777778 -1.907375 +3724 58.7817138889 -2.4555083333 +3725 57.9833333333 -6.8666666667 +3726 57.8333333333 -8.25 +3727 56.7 -8.25 +3728 56.1666666667 -6.9 +3729 56.1 -6.5 +3730 56.5833333333 -5.3666666667 +3731 57.7666666667 -6.1666666667 +3732 57.9833333333 -6.8666666667 +3733 59.0 -4.5 +3734 59.0 -4.6666666667 +3735 59.0 -4.8333333333 +3736 59.0 -5.0 +3737 58.75 -5.0 +3738 58.75 -4.8333333333 +3739 58.75 -4.6666666667 +3740 58.75 -4.5 +3741 59.0 -4.5 +3742 58.75 -4.5 +3743 58.75 -5.0 +3744 58.5333333333 -5.0 +3745 58.5333333333 -4.7911111111 +3746 58.5339416667 -4.7888388889 +3747 58.5369583333 -4.7865 +3748 58.5378888889 -4.7850277778 +3749 58.5385805556 -4.7821583333 +3750 58.5417722222 -4.7800055556 +3751 58.5459583333 -4.7775861111 +3752 58.5516388889 -4.7768333333 +3753 58.5528055556 -4.7810527778 +3754 58.5533666667 -4.7883194444 +3755 58.5545611111 -4.7911638889 +3756 58.5577722222 -4.7964083333 +3757 58.5593583333 -4.7979111111 +3758 58.5609666667 -4.8025111111 +3759 58.5628833333 -4.8052416667 +3760 58.5640527778 -4.8051638889 +3761 58.5669916667 -4.8023027778 +3762 58.5690222222 -4.7998861111 +3763 58.5717833333 -4.7968361111 +3764 58.5734027778 -4.7967944444 +3765 58.5766666667 -4.7955055556 +3766 58.5765305556 -4.7934305556 +3767 58.5773694444 -4.7921222222 +3768 58.5768833333 -4.7896722222 +3769 58.5772 -4.7874611111 +3770 58.5767138889 -4.7850138889 +3771 58.577375 -4.7835194444 +3772 58.5777305556 -4.7754583333 +3773 58.5769166667 -4.7714388889 +3774 58.5764944444 -4.7660694444 +3775 58.5804138889 -4.7634555556 +3776 58.5837444444 -4.7632 +3777 58.5857305556 -4.7669722222 +3778 58.5903944444 -4.7716444444 +3779 58.5910583333 -4.7741055556 +3780 58.5937027778 -4.7765527778 +3781 58.5955916667 -4.7847944444 +3782 58.5985694444 -4.7883027778 +3783 58.5994277778 -4.7902638889 +3784 58.6004083333 -4.7905138889 +3785 58.5996805556 -4.7868416667 +3786 58.6003861111 -4.7832805556 +3787 58.6002472222 -4.7772444444 +3788 58.603275 -4.7743861111 +3789 58.6043916667 -4.7684472222 +3790 58.6033083333 -4.7687055556 +3791 58.601575 -4.7699444444 +3792 58.6004138889 -4.7695083333 +3793 58.5986111111 -4.7655805556 +3794 58.5974638889 -4.7646277778 +3795 58.5951722222 -4.7666861111 +3796 58.5926833333 -4.7654555556 +3797 58.5909777778 -4.7653222222 +3798 58.5883472222 -4.7623583333 +3799 58.5882638889 -4.7578777778 +3800 58.5894555556 -4.7567666667 +3801 58.5878888889 -4.7544055556 +3802 58.586375 -4.7537694444 +3803 58.5836111111 -4.7526916667 +3804 58.5824277778 -4.7491583333 +3805 58.5834333333 -4.7442472222 +3806 58.5842055556 -4.741725 +3807 58.5827722222 -4.7414416667 +3808 58.581375 -4.7396111111 +3809 58.5776666667 -4.7406972222 +3810 58.5747527778 -4.7425333333 +3811 58.5741583333 -4.7409388889 +3812 58.5726361111 -4.7406472222 +3813 58.5696222222 -4.7386916667 +3814 58.5665194444 -4.7324305556 +3815 58.5666777778 -4.729175 +3816 58.5680805556 -4.7267027778 +3817 58.5694555556 -4.7254333333 +3818 58.5701888889 -4.7205027778 +3819 58.5691777778 -4.7173277778 +3820 58.5671916667 -4.7176888889 +3821 58.5639444444 -4.7182972222 +3822 58.56605 -4.7163972222 +3823 58.5687027778 -4.7141944444 +3824 58.5672805556 -4.7092666667 +3825 58.5656694444 -4.7046722222 +3826 58.5640027778 -4.70695 +3827 58.5634138889 -4.7093138889 +3828 58.5607111111 -4.7096194444 +3829 58.5585805556 -4.704125 +3830 58.5571833333 -4.7022972222 +3831 58.5565194444 -4.6996666667 +3832 58.556425 -4.6955333333 +3833 58.5565972222 -4.6915916667 +3834 58.5553777778 -4.6897777778 +3835 58.5553666667 -4.6859944444 +3836 58.5541805556 -4.6826361111 +3837 58.5532722222 -4.6787833333 +3838 58.5518472222 -4.6781583333 +3839 58.5505722222 -4.6789222222 +3840 58.5490555556 -4.6741638889 +3841 58.5504944444 -4.6741 +3842 58.5510305556 -4.6698444444 +3843 58.5506027778 -4.6644805556 +3844 58.5521777778 -4.6621944444 +3845 58.5511583333 -4.6593666667 +3846 58.5518805556 -4.65495 +3847 58.5507444444 -4.6533166667 +3848 58.5478666667 -4.6577416667 +3849 58.5465138889 -4.6579833333 +3850 58.5448166667 -4.6575111111 +3851 58.5444222222 -4.6549027778 +3852 58.5433694444 -4.6536194444 +3853 58.5409333333 -4.6541222222 +3854 58.5403555556 -4.6516722222 +3855 58.5389111111 -4.6519083333 +3856 58.5376833333 -4.6504388889 +3857 58.5347111111 -4.6507305556 +3858 58.5339555556 -4.6525638889 +3859 58.5322361111 -4.6531222222 +3860 58.5279638889 -4.6598416667 +3861 58.5253194444 -4.6617027778 +3862 58.5253333333 -4.6653138889 +3863 58.5264611111 -4.6672888889 +3864 58.5254222222 -4.6697861111 +3865 58.5220222222 -4.6733083333 +3866 58.5200694444 -4.6764222222 +3867 58.5170305556 -4.6799694444 +3868 58.51455 -4.6825277778 +3869 58.5128972222 -4.6842916667 +3870 58.5123861111 -4.6871722222 +3871 58.5093833333 -4.6932972222 +3872 58.5053416667 -4.6931583333 +3873 58.5027055556 -4.6987944444 +3874 58.5004694444 -4.7025694444 +3875 58.4989333333 -4.7072583333 +3876 58.4973472222 -4.7100555556 +3877 58.4951472222 -4.7121166667 +3878 58.4906916667 -4.7145194444 +3879 58.4879416667 -4.7170527778 +3880 58.4867611111 -4.71765 +3881 58.4843666667 -4.7203805556 +3882 58.4816333333 -4.7222277778 +3883 58.4800416667 -4.7251944444 +3884 58.4779416667 -4.7267472222 +3885 58.4753055556 -4.7280861111 +3886 58.4739027778 -4.7307222222 +3887 58.4713055556 -4.7344666667 +3888 58.4680777778 -4.7383333333 +3889 58.4669055556 -4.7385833333 +3890 58.4628361111 -4.7443222222 +3891 58.4611055556 -4.7441861111 +3892 58.4581916667 -4.7425361111 +3893 58.4595888889 -4.7486472222 +3894 58.4564027778 -4.7506277778 +3895 58.453025 -4.7488222222 +3896 58.4507194444 -4.7537166667 +3897 58.4492277778 -4.7582972222 +3898 58.4483916667 -4.7553166667 +3899 58.4495444444 -4.7476916667 +3900 58.4478222222 -4.7484138889 +3901 58.4457388889 -4.7491083333 +3902 58.44615 -4.7467416667 +3903 58.4472222222 -4.7428833333 +3904 58.4485222222 -4.7409277778 +3905 58.4470166667 -4.7356666667 +3906 58.4481611111 -4.7324972222 +3907 58.4530083333 -4.7285888889 +3908 58.4576833333 -4.7243194444 +3909 58.4593861111 -4.7244527778 +3910 58.4635861111 -4.7213472222 +3911 58.4631861111 -4.7148 +3912 58.464325 -4.7119722222 +3913 58.4653305556 -4.7069027778 +3914 58.4666388889 -4.7046027778 +3915 58.4689305556 -4.6980888889 +3916 58.4726861111 -4.694775 +3917 58.4752083333 -4.6944527778 +3918 58.4778388889 -4.6932833333 +3919 58.4780472222 -4.6876361111 +3920 58.4775916667 -4.6836555556 +3921 58.4791777778 -4.6808611111 +3922 58.4818527778 -4.6776333333 +3923 58.4836805556 -4.6717666667 +3924 58.4825055556 -4.6679 +3925 58.482425 -4.6630916667 +3926 58.484625 -4.661025 +3927 58.4868805556 -4.6605111111 +3928 58.490725 -4.6614888889 +3929 58.4935305556 -4.6605 +3930 58.4958638889 -4.660675 +3931 58.4968333333 -4.6616055556 +3932 58.4987361111 -4.6608916667 +3933 58.503 -4.6589833333 +3934 58.5066055556 -4.6583972222 +3935 58.5088194444 -4.6556472222 +3936 58.5106194444 -4.6511444444 +3937 58.5117972222 -4.6507194444 +3938 58.5139166667 -4.6481305556 +3939 58.5156388889 -4.6474027778 +3940 58.5172333333 -4.6442583333 +3941 58.5191388889 -4.6433722222 +3942 58.5207222222 -4.6405694444 +3943 58.5203333333 -4.6376222222 +3944 58.5198111111 -4.6324277778 +3945 58.5219805556 -4.6274388889 +3946 58.52415 -4.6224472222 +3947 58.5236444444 -4.6163972222 +3948 58.5218361111 -4.6169472222 +3949 58.5210638889 -4.6151722222 +3950 58.5184722222 -4.6144638889 +3951 58.5168361111 -4.6153722222 +3952 58.5146777778 -4.6153833333 +3953 58.5135222222 -4.6192472222 +3954 58.5125972222 -4.6205527778 +3955 58.5073277778 -4.6184944444 +3956 58.5078083333 -4.61745 +3957 58.5101333333 -4.6179666667 +3958 58.5122944444 -4.6177833333 +3959 58.5132777778 -4.6135638889 +3960 58.5156555556 -4.6115083333 +3961 58.5205222222 -4.6108388889 +3962 58.5239138889 -4.6076555556 +3963 58.5264444444 -4.6025166667 +3964 58.5266805556 -4.5996138889 +3965 58.5291111111 -4.59945 +3966 58.5318166667 -4.5989638889 +3967 58.5337833333 -4.5949833333 +3968 58.5352138889 -4.5909666667 +3969 58.5369 -4.59195 +3970 58.5407 -4.5906833333 +3971 58.5448138889 -4.591675 +3972 58.54845 -4.5941777778 +3973 58.5526277778 -4.6008472222 +3974 58.55485 -4.6020444444 +3975 58.5585861111 -4.5994 +3976 58.5604805556 -4.594725 +3977 58.5622777778 -4.5946861111 +3978 58.5638361111 -4.5930805556 +3979 58.5657138889 -4.5935638889 +3980 58.566475 -4.5960277778 +3981 58.5676777778 -4.594225 +3982 58.5684222222 -4.597375 +3983 58.5698638889 -4.5973111111 +3984 58.5714111111 -4.5962222222 +3985 58.5727166667 -4.5939083333 +3986 58.5738555556 -4.5908972222 +3987 58.5751055556 -4.5868611111 +3988 58.5754888889 -4.5901583333 +3989 58.5772388889 -4.58805 +3990 58.5775861111 -4.5841194444 +3991 58.5784611111 -4.5809138889 +3992 58.5796583333 -4.5794527778 +3993 58.5805194444 -4.5767638889 +3994 58.5795638889 -4.5751444444 +3995 58.5758833333 -4.570575 +3996 58.5751166667 -4.5684527778 +3997 58.5764361111 -4.5652805556 +3998 58.5775833333 -4.561925 +3999 58.5763972222 -4.55375 +4000 58.5764416667 -4.5515166667 +4001 58.5784 -4.5434027778 +4002 58.5803611111 -4.5442333333 +4003 58.5789222222 -4.5396555556 +4004 58.5788055556 -4.53655 +4005 58.5798166667 -4.5354166667 +4006 58.5786888889 -4.5332722222 +4007 58.5786361111 -4.5269027778 +4008 58.5762333333 -4.5256972222 +4009 58.5757361111 -4.5235944444 +4010 58.5764 -4.52175 +4011 58.5778333333 -4.5173805556 +4012 58.5782527778 -4.5143138889 +4013 58.576525 -4.51075 +4014 58.5759722222 -4.506925 +4015 58.5755166667 -4.5025916667 +4016 58.5763888889 -4.5 +4017 58.75 -4.5 +4018 58.6845611849 -4.8722222222 +4019 58.6843834303 -4.8815454206 +4020 58.6838511206 -4.8908185925 +4021 58.6829671118 -4.8999919843 +4022 58.6817361468 -4.909016387 +4023 58.6801648294 -4.9178434039 +4024 58.6782615883 -4.9264257149 +4025 58.6760366312 -4.9347173328 +4026 58.673501889 -4.9426738539 +4027 58.6706709512 -4.9502526977 +4028 58.6675589918 -4.9574133368 +4029 58.6641826866 -4.9641175159 +4030 58.6605601231 -4.9703294558 +4031 58.6567107024 -4.9760160454 +4032 58.6526550338 -4.981147017 +4033 58.6484148234 -4.9856951069 +4034 58.6440127571 -4.9896361975 +4035 58.6394723782 -4.9929494437 +4036 58.6348179603 -4.9956173795 +4037 58.6300743768 -4.9976260072 +4038 58.6252669678 -4.9989648664 +4039 58.6204214036 -4.9996270849 +4040 58.6155635479 -4.9996094092 +4041 58.610719319 -4.9989122161 +4042 58.6059145521 -4.9975395044 +4043 58.6011748612 -4.9954988679 +4044 58.5965255033 -4.992801449 +4045 58.5919912442 -4.9894618741 +4046 58.587596227 -4.98549817 +4047 58.5833638446 -4.9809316641 +4048 58.5793166162 -4.9757868662 +4049 58.575476068 -4.9700913349 +4050 58.5718626203 -4.9638755284 +4051 58.5684954797 -4.9571726403 +4052 58.5653925384 -4.9500184221 +4053 58.5625702802 -4.9424509926 +4054 58.560043694 -4.9345106356 +4055 58.5578261953 -4.9262395872 +4056 58.5559295563 -4.9176818128 +4057 58.5543638439 -4.9088827764 +4058 58.5531373672 -4.8998892021 +4059 58.5522566345 -4.8907488293 +4060 58.5517263187 -4.8815101633 +4061 58.5515492336 -4.8722222222 +4062 58.5517263187 -4.8629342812 +4063 58.5522566345 -4.8536956152 +4064 58.5531373672 -4.8445552423 +4065 58.5543638439 -4.835561668 +4066 58.5559295563 -4.8267626317 +4067 58.5578261953 -4.8182048573 +4068 58.560043694 -4.8099338088 +4069 58.5625702802 -4.8019934519 +4070 58.5653925384 -4.7944260223 +4071 58.5684954797 -4.7872718041 +4072 58.5718626203 -4.780568916 +4073 58.575476068 -4.7743531095 +4074 58.5793166162 -4.7686575783 +4075 58.5833638446 -4.7635127804 +4076 58.587596227 -4.7589462744 +4077 58.5919912442 -4.7549825704 +4078 58.5965255033 -4.7516429954 +4079 58.6011748612 -4.7489455766 +4080 58.6059145521 -4.7469049401 +4081 58.610719319 -4.7455322283 +4082 58.6155635479 -4.7448350352 +4083 58.6204214036 -4.7448173595 +4084 58.6252669678 -4.745479578 +4085 58.6300743768 -4.7468184373 +4086 58.6348179603 -4.7488270649 +4087 58.6394723782 -4.7514950008 +4088 58.6440127571 -4.7548082469 +4089 58.6484148234 -4.7587493376 +4090 58.6526550338 -4.7632974274 +4091 58.6567107024 -4.7684283991 +4092 58.6605601231 -4.7741149886 +4093 58.6641826866 -4.7803269286 +4094 58.6675589918 -4.7870311076 +4095 58.6706709512 -4.7941917468 +4096 58.673501889 -4.8017705905 +4097 58.6760366312 -4.8097271116 +4098 58.6782615883 -4.8180187296 +4099 58.6801648294 -4.8266010405 +4100 58.6817361468 -4.8354280575 +4101 58.6829671118 -4.8444524601 +4102 58.6838511206 -4.853625852 +4103 58.6843834303 -4.8628990238 +4104 58.6845611849 -4.8722222222 +4105 58.8333333333 -2.5538888889 +4106 58.4333333333 -2.68 +4107 58.4333333333 -2.5133888889 +4108 58.4333333333 -2.3467777778 +4109 58.4333333333 -2.1801666667 +4110 58.4333333333 -2.0135555556 +4111 58.4333333333 -1.8469444444 +4112 58.8333333333 -1.7572222222 +4113 58.8333333333 -1.9165555556 +4114 58.8333333333 -2.0758888889 +4115 58.8333333333 -2.2352222222 +4116 58.8333333333 -2.3945555556 +4117 58.8333333333 -2.5538888889 +4118 59.3833333333 -1.8583333333 +4119 58.9666666667 -2.5111111111 +4120 58.8333333333 -2.5538888889 +4121 58.8333333333 -2.3945555556 +4122 58.8333333333 -2.2352222222 +4123 58.8333333333 -2.0758888889 +4124 58.8333333333 -1.9165555556 +4125 58.8333333333 -1.7572222222 +4126 59.0833333333 -1.7 +4127 59.3833333333 -1.7 +4128 59.3833333333 -1.8583333333 +4129 58.4333333333 -2.68 +4130 58.275 -2.7291666667 +4131 57.8333333333 -2.4041666667 +4132 57.8333333333 -2.262037037 +4133 57.8333333333 -2.1199074074 +4134 57.8333333333 -1.9777777778 +4135 58.4333333333 -1.8469444444 +4136 58.4333333333 -2.0135555556 +4137 58.4333333333 -2.1801666667 +4138 58.4333333333 -2.3467777778 +4139 58.4333333333 -2.5133888889 +4140 58.4333333333 -2.68 +4141 59.6666666667 -1.5 +4142 59.8333333333 -6.0302777778 +4143 58.3222222222 -5.8786111111 +4144 57.6666666667 -2.9725 +4145 57.6666666667 -2.8107407407 +4146 57.6666666667 -2.6489814815 +4147 57.6666666667 -2.4872222222 +4148 57.6666666667 -2.325462963 +4149 57.6666666667 -2.1637037037 +4150 57.6666666667 -2.0019444444 +4151 57.6666666667 -1.8401851852 +4152 57.6666666667 -1.6784259259 +4153 57.6666666667 -1.5166666667 +4154 57.7833333333 -1.0 +4155 58.0375 0.1633333333 +4156 59.1666666667 -1.0 +4157 59.6666666667 -1.5 +4158 56.0918776254 -4.8663888889 +4159 56.0917011577 -4.8725074402 +4160 56.0911736299 -4.878560967 +4161 56.0903006481 -4.8844851413 +4162 56.089091489 -4.8902170197 +4163 56.0875590008 -4.8956957176 +4164 56.0857194653 -4.9008630591 +4165 56.0835924241 -4.9056641986 +4166 56.0812004696 -4.9100482046 +4167 56.0785690036 -4.9139686016 +4168 56.0757259658 -4.9173838627 +4169 56.0727015362 -4.9202578484 +4170 56.069527813 -4.9225601874 +4171 56.0662384706 -4.9242665941 +4172 56.0628684018 -4.9253591212 +4173 56.0594533465 -4.9258263439 +4174 56.056029512 -4.9256634744 +4175 56.0526331894 -4.9248724057 +4176 56.0493003688 -4.9234616844 +4177 56.0460663579 -4.9214464135 +4178 56.0429654094 -4.9188480857 +4179 56.0400303583 -4.9156943503 +4180 56.0372922762 -4.9120187157 +4181 56.0347801428 -4.9078601907 +4182 56.0325205412 -4.9032628694 +4183 56.0305373778 -4.8982754627 +4184 56.0288516311 -4.8929507836 +4185 56.0274811305 -4.887345189 +4186 56.02644037 -4.8815179867 +4187 56.0257403549 -4.8755308106 +4188 56.0253884872 -4.8694469739 +4189 56.0253884872 -4.8633308039 +4190 56.0257403549 -4.8572469672 +4191 56.02644037 -4.8512597911 +4192 56.0274811305 -4.8454325887 +4193 56.0288516311 -4.8398269942 +4194 56.0305373778 -4.8345023151 +4195 56.0325205412 -4.8295149084 +4196 56.0347801428 -4.824917587 +4197 56.0372922762 -4.8207590621 +4198 56.0400303583 -4.8170834275 +4199 56.0429654094 -4.8139296921 +4200 56.0460663579 -4.8113313643 +4201 56.0493003688 -4.8093160933 +4202 56.0526331894 -4.8079053721 +4203 56.056029512 -4.8071143034 +4204 56.0594533465 -4.8069514339 +4205 56.0628684018 -4.8074186566 +4206 56.0662384706 -4.8085111837 +4207 56.069527813 -4.8102175904 +4208 56.0727015362 -4.8125199293 +4209 56.0757259658 -4.8153939151 +4210 56.0785690036 -4.8188091761 +4211 56.0812004696 -4.8227295731 +4212 56.0835924241 -4.8271135792 +4213 56.0857194653 -4.8319147186 +4214 56.0875590008 -4.8370820602 +4215 56.089091489 -4.8425607581 +4216 56.0903006481 -4.8482926365 +4217 56.0911736299 -4.8542168107 +4218 56.0917011577 -4.8602703376 +4219 56.0918776254 -4.8663888889 +4220 58.609642007 -3.7427777778 +4221 58.609465595 -3.7493300434 +4222 58.6089382341 -3.7558126572 +4223 58.6080655301 -3.7621567139 +4224 58.6068567592 -3.7682947936 +4225 58.6053247684 -3.7741616829 +4226 58.6034858381 -3.7796950733 +4227 58.6013595079 -3.7848362261 +4228 58.5989683673 -3.7895305989 +4229 58.5963378139 -3.7937284254 +4230 58.5934957828 -3.7973852435 +4231 58.5904724474 -3.8004623645 +4232 58.5872998982 -3.8029272805 +4233 58.5840118007 -3.8047540042 +4234 58.5806430368 -3.8059233382 +4235 58.5772293343 -3.8064230716 +4236 58.5738068869 -3.8062481016 +4237 58.5704119707 -3.8054004792 +4238 58.5670805596 -3.8038893795 +4239 58.5638479444 -3.8017309962 +4240 58.56074836 -3.7989483623 +4241 58.5578146233 -3.7955710999 +4242 58.5550777877 -3.7916351009 +4243 58.5525668152 -3.7871821421 +4244 58.5503082721 -3.7822594409 +4245 58.5483260487 -3.7769191536 +4246 58.5466411091 -3.7712178237 +4247 58.5452712702 -3.7652157856 +4248 58.5442310155 -3.7589765288 +4249 58.5435313422 -3.7525660311 +4250 58.5431796467 -3.7460520656 +4251 58.5431796467 -3.7395034899 +4252 58.5435313422 -3.7329895244 +4253 58.5442310155 -3.7265790268 +4254 58.5452712702 -3.72033977 +4255 58.5466411091 -3.7143377318 +4256 58.5483260487 -3.708636402 +4257 58.5503082721 -3.7032961146 +4258 58.5525668152 -3.6983734134 +4259 58.5550777877 -3.6939204547 +4260 58.5578146233 -3.6899844556 +4261 58.56074836 -3.6866071933 +4262 58.5638479444 -3.6838245594 +4263 58.5670805596 -3.681666176 +4264 58.5704119707 -3.6801550763 +4265 58.5738068869 -3.679307454 +4266 58.5772293343 -3.6791324839 +4267 58.5806430368 -3.6796322173 +4268 58.5840118007 -3.6808015513 +4269 58.5872998982 -3.682628275 +4270 58.5904724474 -3.6850931911 +4271 58.5934957828 -3.6881703121 +4272 58.5963378139 -3.6918271301 +4273 58.5989683673 -3.6960249567 +4274 58.6013595079 -3.7007193295 +4275 58.6034858381 -3.7058604823 +4276 58.6053247684 -3.7113938727 +4277 58.6068567592 -3.717260762 +4278 58.6080655301 -3.7233988416 +4279 58.6089382341 -3.7297428984 +4280 58.609465595 -3.7362255122 +4281 58.609642007 -3.7427777778 +4282 50.4047047378 -4.1872222222 +4283 50.404527252 -4.1910152222 +4284 50.4039985814 -4.1947272975 +4285 50.403130005 -4.1982792553 +4286 50.4019400528 -4.201595329 +4287 50.4004541095 -4.2046047982 +4288 50.3987038712 -4.2072435002 +4289 50.3967266679 -4.2094551986 +4290 50.3945646657 -4.2111927823 +4291 50.3922639654 -4.2124192668 +4292 50.389873619 -4.2131085786 +4293 50.3874445819 -4.2132461049 +4294 50.3850286269 -4.2128289986 +4295 50.38267724 -4.211866232 +4296 50.3804405238 -4.2103783981 +4297 50.3783661309 -4.2083972659 +4298 50.3764982494 -4.2059650983 +4299 50.3748766639 -4.203133748 +4300 50.373535909 -4.1999635509 +4301 50.372504536 -4.1965220414 +4302 50.3718045064 -4.1928825154 +4303 50.3714507253 -4.1891224728 +4304 50.3714507253 -4.1853219717 +4305 50.3718045064 -4.1815619291 +4306 50.372504536 -4.177922403 +4307 50.373535909 -4.1744808935 +4308 50.3748766639 -4.1713106965 +4309 50.3764982494 -4.1684793461 +4310 50.3783661309 -4.1660471786 +4311 50.3804405238 -4.1640660464 +4312 50.38267724 -4.1625782125 +4313 50.3850286269 -4.1616154458 +4314 50.3874445819 -4.1611983396 +4315 50.389873619 -4.1613358658 +4316 50.3922639654 -4.1620251776 +4317 50.3945646657 -4.1632516622 +4318 50.3967266679 -4.1649892459 +4319 50.3987038712 -4.1672009443 +4320 50.4004541095 -4.1698396462 +4321 50.4019400528 -4.1728491155 +4322 50.403130005 -4.1761651891 +4323 50.4039985814 -4.1797171469 +4324 50.404527252 -4.1834292222 +4325 50.4047047378 -4.1872222222 +4326 50.9469064086 0.9547222222 +4327 50.9467298142 0.949303047 +4328 50.9462019069 0.9439414384 +4329 50.9453282944 0.9386943478 +4330 50.944118256 0.9336175023 +4331 50.9425846441 0.9287648099 +4332 50.9407437458 0.9241877838 +4333 50.9386151102 0.9199349935 +4334 50.9362213387 0.9160515477 +4335 50.9335878442 0.9125786149 +4336 50.9307425803 0.9095529867 +4337 50.9277157431 0.9070066893 +4338 50.9245394495 0.9049666453 +4339 50.921247396 0.9034543919 +4340 50.9178744997 0.9024858558 +4341 50.9144565275 0.9020711889 +4342 50.9110297167 0.9022146659 +4343 50.9076303902 0.9029146436 +4344 50.904294572 0.9041635837 +4345 50.9010576053 0.9059481378 +4346 50.897953779 0.9082492935 +4347 50.8950159648 0.9110425797 +4348 50.8922752704 0.9142983296 +4349 50.8897607111 0.9179819975 +4350 50.8874989035 0.9220545264 +4351 50.8855137854 0.9264727623 +4352 50.8838263633 0.9311899111 +4353 50.8824544915 0.9361560329 +4354 50.881412684 0.9413185687 +4355 50.8807119621 0.9466228939 +4356 50.8803597382 0.9520128933 +4357 50.8803597382 0.9574315512 +4358 50.8807119621 0.9628215506 +4359 50.881412684 0.9681258757 +4360 50.8824544915 0.9732884115 +4361 50.8838263633 0.9782545333 +4362 50.8855137854 0.9829716822 +4363 50.8874989035 0.9873899181 +4364 50.8897607111 0.9914624469 +4365 50.8922752704 0.9951461149 +4366 50.8950159648 0.9984018648 +4367 50.897953779 1.001195151 +4368 50.9010576053 1.0034963066 +4369 50.904294572 1.0052808608 +4370 50.9076303902 1.0065298009 +4371 50.9110297167 1.0072297785 +4372 50.9144565275 1.0073732555 +4373 50.9178744997 1.0069585887 +4374 50.921247396 1.0059900525 +4375 50.9245394495 1.0044777991 +4376 50.9277157431 1.0024377552 +4377 50.9307425803 0.9998914577 +4378 50.9335878442 0.9968658296 +4379 50.9362213387 0.9933928967 +4380 50.9386151102 0.9895094509 +4381 50.9407437458 0.9852566607 +4382 50.9425846441 0.9806796346 +4383 50.944118256 0.9758269422 +4384 50.9453282944 0.9707500967 +4385 50.9462019069 0.965503006 +4386 50.9467298142 0.9601413974 +4387 50.9469064086 0.9547222222 +4388 49.4794001476 -2.3625 +4389 49.4792247688 -2.3689155084 +4390 49.4786998665 -2.3752858801 +4391 49.4778291334 -2.3815662987 +4392 49.4766186951 -2.3877125865 +4393 49.4750770665 -2.3936815175 +4394 49.4732150914 -2.3994311242 +4395 49.4710458655 -2.4049209946 +4396 49.4685846435 -2.410112558 +4397 49.4658487315 -2.414969357 +4398 49.4628573634 -2.4194573051 +4399 49.4596315661 -2.4235449258 +4400 49.4561940094 -2.4272035732 +4401 49.4525688468 -2.4304076327 +4402 49.4487815446 -2.4331346987 +4403 49.4448587019 -2.4353657305 +4404 49.4408278634 -2.4370851827 +4405 49.4367173255 -2.4382811118 +4406 49.4325559366 -2.4389452565 +4407 49.4283728951 -2.439073092 +4408 49.4241975438 -2.4386638582 +4409 49.420059164 -2.437720561 +4410 49.4159867707 -2.4362499477 +4411 49.412008909 -2.4342624555 +4412 49.4081534549 -2.4317721356 +4413 49.4044474198 -2.4287965508 +4414 49.4009167627 -2.4253566504 +4415 49.3975862086 -2.4214766204 +4416 49.3944790766 -2.4171837129 +4417 49.3916171169 -2.4125080535 +4418 49.3890203603 -2.4074824296 +4419 49.3867069782 -2.4021420611 +4420 49.3846931567 -2.3965243537 +4421 49.382992984 -2.3906686384 +4422 49.3816183531 -2.3846158977 +4423 49.3805788785 -2.3784084803 +4424 49.3798818303 -2.3720898073 +4425 49.3795320833 -2.3657040712 +4426 49.3795320833 -2.3592959288 +4427 49.3798818303 -2.3529101927 +4428 49.3805788785 -2.3465915197 +4429 49.3816183531 -2.3403841023 +4430 49.382992984 -2.3343313616 +4431 49.3846931567 -2.3284756463 +4432 49.3867069782 -2.3228579389 +4433 49.3890203603 -2.3175175704 +4434 49.3916171169 -2.3124919465 +4435 49.3944790766 -2.3078162871 +4436 49.3975862086 -2.3035233796 +4437 49.4009167627 -2.2996433496 +4438 49.4044474198 -2.2962034492 +4439 49.4081534549 -2.2932278644 +4440 49.412008909 -2.2907375445 +4441 49.4159867707 -2.2887500523 +4442 49.420059164 -2.287279439 +4443 49.4241975438 -2.2863361418 +4444 49.4283728951 -2.285926908 +4445 49.4325559366 -2.2860547435 +4446 49.4367173255 -2.2867188882 +4447 49.4408278634 -2.2879148173 +4448 49.4448587019 -2.2896342695 +4449 49.4487815446 -2.2918653013 +4450 49.4525688468 -2.2945923673 +4451 49.4561940094 -2.2977964268 +4452 49.4596315661 -2.3014550742 +4453 49.4628573634 -2.3055426949 +4454 49.4658487315 -2.310030643 +4455 49.4685846435 -2.314887442 +4456 49.4710458655 -2.3200790054 +4457 49.4732150914 -2.3255688758 +4458 49.4750770665 -2.3313184825 +4459 49.4766186951 -2.3372874135 +4460 49.4778291334 -2.3434337013 +4461 49.4786998665 -2.3497141199 +4462 49.4792247688 -2.3560844916 +4463 49.4794001476 -2.3625 +4464 51.3924695424 -1.1463888889 +4465 51.3922941889 -1.1511093435 +4466 51.391770594 -1.1557634263 +4467 51.3909061194 -1.1602857032 +4468 51.3897129191 -1.164612602 +4469 51.3882077678 -1.16868331 +4470 51.3864118238 -1.1724406312 +4471 51.3843503304 -1.1758317931 +4472 51.3820522599 -1.1788091878 +4473 51.3795499048 -1.1813310418 +4474 51.376878423 -1.1833620001 +4475 51.374075342 -1.1848736205 +4476 51.3711800313 -1.1858447687 +4477 51.3682331481 -1.1862619106 +4478 51.3652760659 -1.1861192962 +4479 51.3623502939 -1.1854190348 +4480 51.3594968935 -1.1841710595 +4481 51.3567559032 -1.1823929815 +4482 51.3541657774 -1.1801098382 +4483 51.3517628473 -1.177353737 +4484 51.3495808134 -1.174163402 +4485 51.3476502732 -1.1705836278 +4486 51.3459982944 -1.1666646506 +4487 51.3446480361 -1.1624614438 +4488 51.3436184261 -1.1580329486 +4489 51.342923896 -1.1534412499 +4490 51.3425741802 -1.1487507096 +4491 51.3425741802 -1.1440270682 +4492 51.342923896 -1.1393365279 +4493 51.3436184261 -1.1347448292 +4494 51.3446480361 -1.130316334 +4495 51.3459982944 -1.1261131272 +4496 51.3476502732 -1.12219415 +4497 51.3495808134 -1.1186143758 +4498 51.3517628473 -1.1154240407 +4499 51.3541657774 -1.1126679396 +4500 51.3567559032 -1.1103847963 +4501 51.3594968935 -1.1086067183 +4502 51.3623502939 -1.1073587429 +4503 51.3652760659 -1.1066584816 +4504 51.3682331481 -1.1065158672 +4505 51.3711800313 -1.106933009 +4506 51.374075342 -1.1079041573 +4507 51.376878423 -1.1094157777 +4508 51.3795499048 -1.111446736 +4509 51.3820522599 -1.1139685899 +4510 51.3843503304 -1.1169459847 +4511 51.3864118238 -1.1203371465 +4512 51.3882077678 -1.1240944678 +4513 51.3897129191 -1.1281651757 +4514 51.3909061194 -1.1324920746 +4515 51.391770594 -1.1370143515 +4516 51.3922941889 -1.1416684343 +4517 51.3924695424 -1.1463888889 +4518 51.4233129283 -1.0236111111 +4519 51.4231354714 -1.0274878214 +4520 51.4226068868 -1.0312818179 +4521 51.4217384523 -1.0349121572 +4522 51.4205486955 -1.0383013983 +4523 51.4190629976 -1.0413772588 +4524 51.4173130507 -1.0440741597 +4525 51.4153361794 -1.0463346245 +4526 51.4131745437 -1.0481105042 +4527 51.4108742375 -1.0493640011 +4528 51.4084843048 -1.0500684699 +4529 51.4060556927 -1.0502089796 +4530 51.403640165 -1.0497826245 +4531 51.4012891983 -1.0487985788 +4532 51.3990528858 -1.0472778936 +4533 51.3969788707 -1.0452530415 +4534 51.3951113324 -1.0427672195 +4535 51.3934900469 -1.0398734246 +4536 51.3921495417 -1.0366333234 +4537 51.3911183617 -1.033115938 +4538 51.3904184636 -1.0293961781 +4539 51.3900647491 -1.0255532497 +4540 51.3900647491 -1.0216689725 +4541 51.3904184636 -1.0178260441 +4542 51.3911183617 -1.0141062843 +4543 51.3921495417 -1.0105888988 +4544 51.3934900469 -1.0073487976 +4545 51.3951113324 -1.0044550028 +4546 51.3969788707 -1.0019691807 +4547 51.3990528858 -0.9999443286 +4548 51.4012891983 -0.9984236434 +4549 51.403640165 -0.9974395977 +4550 51.4060556927 -0.9970132426 +4551 51.4084843048 -0.9971537523 +4552 51.4108742375 -0.9978582211 +4553 51.4131745437 -0.999111718 +4554 51.4153361794 -1.0008875977 +4555 51.4173130507 -1.0031480625 +4556 51.4190629976 -1.0058449634 +4557 51.4205486955 -1.008920824 +4558 51.4217384523 -1.012310065 +4559 51.4226068868 -1.0159404043 +4560 51.4231354714 -1.0197344008 +4561 51.4233129283 -1.0236111111 +4562 51.6471906741 -2.1805555556 +4563 51.6470153274 -2.1853024165 +4564 51.6464917528 -2.1899825335 +4565 51.6456273118 -2.1945301052 +4566 51.6444341583 -2.1988812033 +4567 51.6429290662 -2.2029746741 +4568 51.6411331935 -2.2067530014 +4569 51.6390717828 -2.2101631173 +4570 51.6367738055 -2.2131571481 +4571 51.6342715531 -2.2156930867 +4572 51.6316001822 -2.2177353812 +4573 51.6287972192 -2.2192554313 +4574 51.625902032 -2.2202319857 +4575 51.6229552762 -2.2206514358 +4576 51.6199983237 -2.2205080007 +4577 51.6170726815 -2.219803803 +4578 51.6142194095 -2.2185488324 +4579 51.6114785441 -2.2167607997 +4580 51.6088885376 -2.2144648831 +4581 51.6064857195 -2.2116933704 +4582 51.6043037882 -2.2084852023 +4583 51.6023733396 -2.204885424 +4584 51.6007214398 -2.2009445523 +4585 51.5993712465 -2.1967178674 +4586 51.5983416863 -2.1922646389 +4587 51.5976471898 -2.1876472979 +4588 51.5972974911 -2.1829305648 +4589 51.5972974911 -2.1781805463 +4590 51.5976471898 -2.1734638132 +4591 51.5983416863 -2.1688464722 +4592 51.5993712465 -2.1643932438 +4593 51.6007214398 -2.1601665588 +4594 51.6023733396 -2.1562256871 +4595 51.6043037882 -2.1526259088 +4596 51.6064857195 -2.1494177407 +4597 51.6088885376 -2.146646228 +4598 51.6114785441 -2.1443503114 +4599 51.6142194095 -2.1425622788 +4600 51.6170726815 -2.1413073081 +4601 51.6199983237 -2.1406031104 +4602 51.6229552762 -2.1404596754 +4603 51.625902032 -2.1408791254 +4604 51.6287972192 -2.1418556798 +4605 51.6316001822 -2.1433757299 +4606 51.6342715531 -2.1454180245 +4607 51.6367738055 -2.147953963 +4608 51.6390717828 -2.1509479938 +4609 51.6411331935 -2.1543581097 +4610 51.6429290662 -2.1581364371 +4611 51.6444341583 -2.1622299078 +4612 51.6456273118 -2.1665810059 +4613 51.6464917528 -2.1711285777 +4614 51.6470153274 -2.1758086946 +4615 51.6471906741 -2.1805555556 +4616 51.4397017704 -2.1127777778 +4617 51.4395243139 -2.1166558753 +4618 51.4389957307 -2.1204512294 +4619 51.4381272985 -2.1240828677 +4620 51.4369375448 -2.1274733213 +4621 51.4354518509 -2.1305502821 +4622 51.4337019086 -2.1332481474 +4623 51.4317250426 -2.1355094204 +4624 51.4295634128 -2.1372859347 +4625 51.4272631129 -2.1385398793 +4626 51.4248731868 -2.1392445993 +4627 51.4224445816 -2.1393851584 +4628 51.4200290607 -2.13895865 +4629 51.4176781007 -2.1379742516 +4630 51.4154417947 -2.136453022 +4631 51.4133677857 -2.1344274453 +4632 51.4115002529 -2.1319407342 +4633 51.4098789722 -2.1290459045 +4634 51.408538471 -2.1258046448 +4635 51.4075072941 -2.122286002 +4636 51.4068073981 -2.1185649125 +4637 51.4064536847 -2.1147206105 +4638 51.4064536847 -2.110834945 +4639 51.4068073981 -2.106990643 +4640 51.4075072941 -2.1032695536 +4641 51.408538471 -2.0997509107 +4642 51.4098789722 -2.096509651 +4643 51.4115002529 -2.0936148214 +4644 51.4133677857 -2.0911281102 +4645 51.4154417947 -2.0891025336 +4646 51.4176781007 -2.0875813039 +4647 51.4200290607 -2.0865969056 +4648 51.4224445816 -2.0861703972 +4649 51.4248731868 -2.0863109563 +4650 51.4272631129 -2.0870156763 +4651 51.4295634128 -2.0882696209 +4652 51.4317250426 -2.0900461352 +4653 51.4337019086 -2.0923074081 +4654 51.4354518509 -2.0950052735 +4655 51.4369375448 -2.0980822343 +4656 51.4381272985 -2.1014726879 +4657 51.4389957307 -2.1051043261 +4658 51.4395243139 -2.1088996802 +4659 51.4397017704 -2.1127777778 +4660 51.2423352721 -3.1301805556 +4661 51.2421586853 -3.1356343719 +4662 51.2416308009 -3.1410302524 +4663 51.2407572264 -3.1463108803 +4664 51.239547241 -3.1514201712 +4665 51.2380136966 -3.1563038717 +4666 51.2361728802 -3.1609101384 +4667 51.2340443402 -3.1651900912 +4668 51.2316506773 -3.1690983329 +4669 51.229017304 -3.1725934322 +4670 51.2261721727 -3.1756383627 +4671 51.2231454786 -3.1782008946 +4672 51.2199693375 -3.1802539342 +4673 51.2166774443 -3.1817758082 +4674 51.2133047149 -3.1827504897 +4675 51.2098869144 -3.1831677634 +4676 51.2064602785 -3.1830233292 +4677 51.2030611281 -3.1823188426 +4678 51.1997254852 -3.1810618915 +4679 51.1964886911 -3.1792659112 +4680 51.1933850325 -3.1769500369 +4681 51.190447379 -3.1741388969 +4682 51.1877068364 -3.1708623484 +4683 51.1851924178 -3.167155158 +4684 51.182930738 -3.1630566323 +4685 51.180945733 -3.1586102005 +4686 51.1792584078 -3.153862955 +4687 51.1778866152 -3.1488651536 +4688 51.1768448681 -3.1436696898 +4689 51.176144187 -3.1383315354 +4690 51.1757919837 -3.1329071624 +4691 51.1757919837 -3.1274539487 +4692 51.176144187 -3.1220295757 +4693 51.1768448681 -3.1166914213 +4694 51.1778866152 -3.1114959575 +4695 51.1792584078 -3.1064981561 +4696 51.180945733 -3.1017509106 +4697 51.182930738 -3.0973044788 +4698 51.1851924178 -3.0932059531 +4699 51.1877068364 -3.0894987627 +4700 51.190447379 -3.0862222142 +4701 51.1933850325 -3.0834110742 +4702 51.1964886911 -3.0810951999 +4703 51.1997254852 -3.0792992196 +4704 51.2030611281 -3.0780422685 +4705 51.2064602785 -3.0773377819 +4706 51.2098869144 -3.0771933477 +4707 51.2133047149 -3.0776106214 +4708 51.2166774443 -3.0785853029 +4709 51.2199693375 -3.0801071769 +4710 51.2231454786 -3.0821602165 +4711 51.2261721727 -3.0847227484 +4712 51.229017304 -3.0877676789 +4713 51.2316506773 -3.0912627782 +4714 51.2340443402 -3.0951710199 +4715 51.2361728802 -3.0994509727 +4716 51.2380136966 -3.1040572394 +4717 51.239547241 -3.1089409399 +4718 51.2407572264 -3.1140502308 +4719 51.2416308009 -3.1193308587 +4720 51.2421586853 -3.1247267392 +4721 51.2423352721 -3.1301805556 +4722 51.6811522104 -2.5708638889 +4723 51.6809756349 -2.5763702602 +4724 51.6804477843 -2.5818181352 +4725 51.6795742659 -2.5871496433 +4726 51.6783643587 -2.5923081578 +4727 51.6768309141 -2.597238901 +4728 51.6749902186 -2.6018895292 +4729 51.6728618197 -2.6062106904 +4730 51.6704683175 -2.6101565501 +4731 51.6678351232 -2.613685278 +4732 51.664990188 -2.6167594919 +4733 51.6619637055 -2.6193466528 +4734 51.6587877899 -2.6214194077 +4735 51.6554961341 -2.6229558766 +4736 51.6521236517 -2.6239398805 +4737 51.6487061056 -2.6243611085 +4738 51.6452797286 -2.6242152215 +4739 51.6418808392 -2.6235038936 +4740 51.6385454562 -2.6222347885 +4741 51.6353089179 -2.6204214729 +4742 51.6322055079 -2.6180832685 +4743 51.6292680929 -2.6152450422 +4744 51.6265277754 -2.6119369398 +4745 51.6240135655 -2.6081940633 +4746 51.6217520754 -2.6040560978 +4747 51.6197672383 -2.5995668902 +4748 51.6180800568 -2.5947739853 +4749 51.6167083818 -2.5897281231 +4750 51.6156667245 -2.5844827046 +4751 51.6149661039 -2.5790932284 +4752 51.6146139311 -2.5736167077 +4753 51.6146139311 -2.5681110701 +4754 51.6149661039 -2.5626345494 +4755 51.6156667245 -2.5572450732 +4756 51.6167083818 -2.5519996547 +4757 51.6180800568 -2.5469537925 +4758 51.6197672383 -2.5421608876 +4759 51.6217520754 -2.53767168 +4760 51.6240135655 -2.5335337145 +4761 51.6265277754 -2.529790838 +4762 51.6292680929 -2.5264827356 +4763 51.6322055079 -2.5236445093 +4764 51.6353089179 -2.5213063049 +4765 51.6385454562 -2.5194929893 +4766 51.6418808392 -2.5182238841 +4767 51.6452797286 -2.5175125563 +4768 51.6487061056 -2.5173666693 +4769 51.6521236517 -2.5177878972 +4770 51.6554961341 -2.5187719012 +4771 51.6587877899 -2.5203083701 +4772 51.6619637055 -2.522381125 +4773 51.664990188 -2.5249682859 +4774 51.6678351232 -2.5280424998 +4775 51.6704683175 -2.5315712277 +4776 51.6728618197 -2.5355170874 +4777 51.6749902186 -2.5398382486 +4778 51.6768309141 -2.5444888768 +4779 51.6783643587 -2.54941962 +4780 51.6795742659 -2.5545781345 +4781 51.6804477843 -2.5599096425 +4782 51.6809756349 -2.5653575176 +4783 51.6811522104 -2.5708638889 +4784 51.7260130658 -2.4933 +4785 51.7258364915 -2.4988118196 +4786 51.7253086443 -2.504265085 +4787 51.7244351316 -2.5096018678 +4788 51.7232252324 -2.5147654852 +4789 51.7216917979 -2.5197011053 +4790 51.7198511147 -2.5243563324 +4791 51.7177227303 -2.5286817657 +4792 51.7153292444 -2.5326315251 +4793 51.7126960683 -2.5361637393 +4794 51.7098511531 -2.539240989 +4795 51.7068246922 -2.5418307031 +4796 51.7036487996 -2.5439055018 +4797 51.700357168 -2.5454434837 +4798 51.6969847108 -2.5464284541 +4799 51.6935671906 -2.5468500919 +4800 51.6901408401 -2.5467040542 +4801 51.6867419773 -2.5459920171 +4802 51.6834066208 -2.5447216519 +4803 51.6801701086 -2.5429065392 +4804 51.6770667241 -2.5405660198 +4805 51.6741293334 -2.5377249855 +4806 51.6713890388 -2.5344136119 +4807 51.6688748503 -2.5306670359 +4808 51.6666133795 -2.5265249817 +4809 51.6646285596 -2.5220313396 +4810 51.6629413928 -2.5172337012 +4811 51.6615697298 -2.5121828567 +4812 51.6605280817 -2.5069322595 +4813 51.6598274673 -2.5015374629 +4814 51.6594752976 -2.4960555361 +4815 51.6594752976 -2.4905444639 +4816 51.6598274673 -2.4850625371 +4817 51.6605280817 -2.4796677405 +4818 51.6615697298 -2.4744171433 +4819 51.6629413928 -2.4693662988 +4820 51.6646285596 -2.4645686604 +4821 51.6666133795 -2.4600750183 +4822 51.6688748503 -2.4559329641 +4823 51.6713890388 -2.4521863881 +4824 51.6741293334 -2.4488750145 +4825 51.6770667241 -2.4460339802 +4826 51.6801701086 -2.4436934608 +4827 51.6834066208 -2.4418783481 +4828 51.6867419773 -2.4406079829 +4829 51.6901408401 -2.4398959458 +4830 51.6935671906 -2.4397499081 +4831 51.6969847108 -2.4401715459 +4832 51.700357168 -2.4411565163 +4833 51.7036487996 -2.4426944982 +4834 51.7068246922 -2.4447692969 +4835 51.7098511531 -2.447359011 +4836 51.7126960683 -2.4504362607 +4837 51.7153292444 -2.4539684749 +4838 51.7177227303 -2.4579182343 +4839 51.7198511147 -2.4622436676 +4840 51.7216917979 -2.4668988947 +4841 51.7232252324 -2.4718345148 +4842 51.7244351316 -2.4769981322 +4843 51.7253086443 -2.482334915 +4844 51.7258364915 -2.4877881804 +4845 51.7260130658 -2.4933 +4846 51.5046964329 -0.6038888889 +4847 51.504518341 -0.6082407864 +4848 51.5039871169 -0.6125181214 +4849 51.5031118618 -0.6166476141 +4850 51.5019075706 -0.6205585275 +4851 51.5003948741 -0.6241838831 +4852 51.4985996837 -0.6274616116 +4853 51.4965527468 -0.630335617 +4854 51.4942891181 -0.6327567375 +4855 51.4918475578 -0.634683586 +4856 51.4892698664 -0.6360832551 +4857 51.4866001681 -0.6369318764 +4858 51.4838841541 -0.6372150232 +4859 51.4811683001 -0.6369279509 +4860 51.4784990711 -0.6360756717 +4861 51.4759221263 -0.6346728614 +4862 51.4734815389 -0.6327436027 +4863 51.4712190432 -0.630320967 +4864 51.4691733222 -0.6274464448 +4865 51.4673793477 -0.6241692331 +4866 51.4658677841 -0.6205453926 +4867 51.4646644659 -0.6166368896 +4868 51.4637899573 -0.612510538 +4869 51.4632592024 -0.6082368609 +4870 51.4630812707 -0.6038888889 +4871 51.4632592024 -0.5995409168 +4872 51.4637899573 -0.5952672398 +4873 51.4646644659 -0.5911408882 +4874 51.4658677841 -0.5872323852 +4875 51.4673793477 -0.5836085447 +4876 51.4691733222 -0.580331333 +4877 51.4712190432 -0.5774568108 +4878 51.4734815389 -0.5750341751 +4879 51.4759221263 -0.5731049163 +4880 51.4784990711 -0.5717021061 +4881 51.4811683001 -0.5708498268 +4882 51.4838841541 -0.5705627546 +4883 51.4866001681 -0.5708459014 +4884 51.4892698664 -0.5716945227 +4885 51.4918475578 -0.5730941918 +4886 51.4942891181 -0.5750210402 +4887 51.4965527468 -0.5774421608 +4888 51.4985996837 -0.5803161661 +4889 51.5003948741 -0.5835938946 +4890 51.5019075706 -0.5872192503 +4891 51.5031118618 -0.5911301637 +4892 51.5039871169 -0.5952596563 +4893 51.504518341 -0.5995369914 +4894 51.5046964329 -0.6038888889 +4895 51.5366111111 -0.1529333333 +4896 51.5378940871 -0.1549267573 +4897 51.5389111961 -0.1572818369 +4898 51.5396236997 -0.1599088899 +4899 51.5400044583 -0.1627078613 +4900 51.5400389683 -0.1655721364 +4901 51.5397259152 -0.1683926087 +4902 51.5390772237 -0.1710618431 +4903 51.5381176028 -0.1734781752 +4904 51.5368836029 -0.1755495885 +4905 51.5354222222 -0.1771972222 +4906 51.5076638889 -0.2023722222 +4907 51.5060699613 -0.2035115549 +4908 51.5043699176 -0.2041447262 +4909 51.5026257804 -0.2042494731 +4910 51.5009009245 -0.2038220493 +4911 51.4992580171 -0.2028780428 +4912 51.4977567415 -0.2014518003 +4913 51.4964516304 -0.1995951734 +4914 51.4953900866 -0.1973756297 +4915 51.4946106635 -0.1948738011 +4916 51.4941416667 -0.1921805556 +4917 51.4890388889 -0.1464694444 +4918 51.482875 -0.1468722222 +4919 51.4811955082 -0.1467340709 +4920 51.4795600798 -0.1461068208 +4921 51.4780238809 -0.1450111174 +4922 51.4766387391 -0.1434839716 +4923 51.4754513811 -0.141576937 +4924 51.4745018581 -0.1393543671 +4925 51.473822197 -0.1368912443 +4926 51.4734353207 -0.1342706517 +4927 51.4733542773 -0.1315809745 +4928 51.4735818 -0.1289129236 +4929 51.4741102153 -0.1263564821 +4930 51.4749217016 -0.1239978753 +4931 51.4759888889 -0.1219166667 +4932 51.4811111111 -0.1136111111 +4933 51.482252708 -0.1120090522 +4934 51.483560414 -0.1107683543 +4935 51.4849782611 -0.109891236 +4936 51.4864671731 -0.1094019057 +4937 51.4879861111 -0.1093138889 +4938 51.5003194444 -0.1102416667 +4939 51.5017362939 -0.1105268172 +4940 51.5031083023 -0.1111609871 +4941 51.504402069 -0.1121293381 +4942 51.5055861111 -0.1134083333 +4943 51.5366111111 -0.1529333333 +4944 51.5237138889 -0.096525 +4945 51.5188833333 -0.1147444444 +4946 51.5102972222 -0.1176944444 +4947 51.5044888889 -0.0757138889 +4948 51.5120666667 -0.0716472222 +4949 51.5216055556 -0.0775861111 +4950 51.5237138889 -0.096525 +4951 51.5097055556 -0.0068583333 +4952 51.5111814939 -0.0082867913 +4953 51.5123684169 -0.0103077723 +4954 51.5132988323 -0.0126486151 +4955 51.5139399674 -0.0152268831 +4956 51.514269238 -0.0179517632 +4957 51.514275045 -0.020727269 +4958 51.5139571838 -0.0234556276 +4959 51.5133268516 -0.0260407298 +4960 51.5124062522 -0.0283915214 +4961 51.5112278124 -0.030425215 +4962 51.5098330386 -0.0320702078 +4963 51.5082710525 -0.0332686036 +4964 51.5065968595 -0.0339782479 +4965 51.5048694103 -0.0341742076 +4966 51.5031495242 -0.0338496416 +4967 51.5014977474 -0.033016033 +4968 51.4999722222 -0.0317027778 +4969 51.4891111111 -0.0202666667 +4970 51.4881604117 -0.0187899397 +4971 51.4874451822 -0.0170196811 +4972 51.4870446916 -0.0150110296 +4973 51.4869869497 -0.0129044713 +4974 51.4872759947 -0.0108473335 +4975 51.4878916114 -0.0089834902 +4976 51.4887907435 -0.0074433086 +4977 51.4899105027 -0.0063345359 +4978 51.4911725642 -0.005734762 +4979 51.4924886427 -0.005685986 +4980 51.4937666667 -0.0061916667 +4981 51.4984027778 -0.0092722222 +4982 51.5097055556 -0.0068583333 +4983 52.2471767692 1.6186111111 +4984 52.2470002081 1.6130349418 +4985 52.2464724007 1.6075180128 +4986 52.2455989541 1.602118931 +4987 52.2443891468 1.596895043 +4988 52.2428558299 1.5919018227 +4989 52.241015289 1.5871922788 +4990 52.2388870708 1.5828163894 +4991 52.2364937743 1.5788205702 +4992 52.2338608093 1.5752471812 +4993 52.2310161253 1.5721340772 +4994 52.2279899142 1.5695142078 +4995 52.2248142877 1.5674152705 +4996 52.2215229365 1.5658594196 +4997 52.2181507711 1.5648630359 +4998 52.2147335516 1.5644365577 +4999 52.2113075073 1.5645843754 +5000 52.2079089532 1.5653047901 +5001 52.2045739043 1.5665900379 +5002 52.201337695 1.5684263769 +5003 52.198234605 1.5707942383 +5004 52.1952974968 1.5736684378 +5005 52.192557469 1.5770184465 +5006 52.190043528 1.5808087168 +5007 52.1877822821 1.5849990611 +5008 52.1857976613 1.5895450777 +5009 52.184110665 1.5943986212 +5010 52.1827391416 1.5995083107 +5011 52.1816975999 1.6048200718 +5012 52.1809970574 1.6102777059 +5013 52.1806449239 1.6158234815 +5014 52.1806449239 1.6213987407 +5015 52.1809970574 1.6269445163 +5016 52.1816975999 1.6324021504 +5017 52.1827391416 1.6377139115 +5018 52.184110665 1.642823601 +5019 52.1857976613 1.6476771445 +5020 52.1877822821 1.6522231611 +5021 52.190043528 1.6564135054 +5022 52.192557469 1.6602037757 +5023 52.1952974968 1.6635537844 +5024 52.198234605 1.6664279839 +5025 52.201337695 1.6687958453 +5026 52.2045739043 1.6706321843 +5027 52.2079089532 1.6719174321 +5028 52.2113075073 1.6726378469 +5029 52.2147335516 1.6727856645 +5030 52.2181507711 1.6723591863 +5031 52.2215229365 1.6713628027 +5032 52.2248142877 1.6698069517 +5033 52.2279899142 1.6677080144 +5034 52.2310161253 1.6650881451 +5035 52.2338608093 1.661975041 +5036 52.2364937743 1.658401652 +5037 52.2388870708 1.6544058329 +5038 52.241015289 1.6500299435 +5039 52.2428558299 1.6453203995 +5040 52.2443891468 1.6403271792 +5041 52.2455989541 1.6351032913 +5042 52.2464724007 1.6297042095 +5043 52.2470002081 1.6241872805 +5044 52.2471767692 1.6186111111 +5045 52.8052777778 0.5177777778 +5046 52.8094444444 0.5861111111 +5047 52.8091625577 0.5813312013 +5048 52.8092184194 0.5765296282 +5049 52.8096115099 0.5717711605 +5050 52.8103365217 0.5671200484 +5051 52.8113836653 0.5626390999 +5052 52.8127388006 0.5583888366 +5053 52.8143836274 0.5544266794 +5054 52.8162959307 0.5508061755 +5055 52.8184498803 0.5475762763 +5056 52.8208163777 0.5447806761 +5057 52.8233634481 0.5424572208 +5058 52.8260566712 0.5406373936 +5059 52.8288596452 0.5393458868 +5060 52.8317344777 0.5386002629 +5061 52.8346422975 0.5384107123 +5062 52.8375437796 0.5387799094 +5063 52.8403996768 0.5397029712 +5064 52.8431713511 0.5411675166 +5065 52.8458212968 0.5431538286 +5066 52.8483136486 0.5456351161 +5067 52.8506146684 0.5485778725 +5068 52.8526932029 0.5519423253 +5069 52.8545211069 0.5556829735 +5070 52.8560736255 0.559749202 +5071 52.8573297311 0.5640859678 +5072 52.8582724089 0.5686345472 +5073 52.8588888889 0.5733333333 +5074 52.8547222222 0.5091666667 +5075 52.8542266656 0.5044716918 +5076 52.8534221775 0.4998968511 +5077 52.8523021167 0.4955069903 +5078 52.8508815899 0.4913613019 +5079 52.8491797549 0.4875156698 +5080 52.8472195607 0.4840219144 +5081 52.8450274369 0.4809270925 +5082 52.8426329362 0.4782728636 +5083 52.8400683345 0.4760949294 +5084 52.8373681946 0.4744225554 +5085 52.8345688996 0.4732781803 +5086 52.8317081614 0.4726771184 +5087 52.8288245125 0.4726273583 +5088 52.825956786 0.4731294608 +5089 52.8231435933 0.4741765578 +5090 52.8204228042 0.4757544502 +5091 52.8178310377 0.4778418043 +5092 52.81540317 0.4804104435 +5093 52.8131718661 0.483425732 +5094 52.8111671417 0.4868470429 +5095 52.8094159609 0.4906283068 +5096 52.8079418741 0.4947186319 +5097 52.8067647034 0.4990629881 +5098 52.8059002767 0.5036029447 +5099 52.8053602162 0.5082774536 +5100 52.8051517825 0.513023667 +5101 52.8052777778 0.5177777778 +5102 52.859129963 0.5797222222 +5103 52.8589546483 0.5748442042 +5104 52.8584311691 0.5700347793 +5105 52.8575668864 0.5653615715 +5106 52.8563739525 0.5608902795 +5107 52.8548691396 0.5566837497 +5108 52.8530736028 0.5528010891 +5109 52.8510125816 0.5492968325 +5110 52.8487150433 0.5462201754 +5111 52.846213275 0.5436142829 +5112 52.8435424277 0.5415156856 +5113 52.8407400216 0.539953769 +5114 52.8378454177 0.5389503657 +5115 52.8348992641 0.5385194541 +5116 52.8319429244 0.5386669678 +5117 52.829017897 0.5393907192 +5118 52.8261652326 0.5406804363 +5119 52.8234249585 0.5425179136 +5120 52.8208355175 0.5448772732 +5121 52.8184332298 0.5477253323 +5122 52.8162517851 0.5510220733 +5123 52.814321771 0.5547212068 +5124 52.8126702457 0.5587708226 +5125 52.8113203607 0.5631141169 +5126 52.8102910367 0.5676901877 +5127 52.8095967002 0.5724348857 +5128 52.8092470821 0.5772817097 +5129 52.8092470821 0.5821627347 +5130 52.8095967002 0.5870095588 +5131 52.8102910367 0.5917542567 +5132 52.8113203607 0.5963303275 +5133 52.8126702457 0.6006736219 +5134 52.814321771 0.6047232376 +5135 52.8162517851 0.6084223711 +5136 52.8184332298 0.6117191121 +5137 52.8208355175 0.6145671713 +5138 52.8234249585 0.6169265308 +5139 52.8261652326 0.6187640082 +5140 52.829017897 0.6200537253 +5141 52.8319429244 0.6207774766 +5142 52.8348992641 0.6209249903 +5143 52.8378454177 0.6204940787 +5144 52.8407400216 0.6194906755 +5145 52.8435424277 0.6179287589 +5146 52.846213275 0.6158301615 +5147 52.8487150433 0.613224269 +5148 52.8510125816 0.6101476119 +5149 52.8530736028 0.6066433553 +5150 52.8548691396 0.6027606947 +5151 52.8563739525 0.5985541649 +5152 52.8575668864 0.594082873 +5153 52.8584311691 0.5894096651 +5154 52.8589546483 0.5846002403 +5155 52.859129963 0.5797222222 +5156 53.2971708423 -2.9522222222 +5157 53.2969943076 -2.9579341894 +5158 53.2964665791 -2.9635854683 +5159 53.2955932635 -2.9691160199 +5160 53.2943836389 -2.9744670965 +5161 53.2928505553 -2.9795818698 +5162 53.2910102972 -2.9844060374 +5163 53.2888824097 -2.9888884027 +5164 53.2864894898 -2.9929814192 +5165 53.2838569448 -2.9966416966 +5166 53.2810127215 -2.9998304605 +5167 53.2779870081 -3.0025139625 +5168 53.2748119126 -3.0046638354 +5169 53.2715211209 -3.0062573909 +5170 53.2681495386 -3.0072778557 +5171 53.26473292 -3.0077145442 +5172 53.2613074885 -3.0075629662 +5173 53.2579095522 -3.0068248687 +5174 53.2545751195 -3.0055082113 +5175 53.2513395174 -3.0036270764 +5176 53.248237018 -3.0012015142 +5177 53.2453004767 -2.9982573261 +5178 53.2425609844 -2.9948257867 +5179 53.2400475405 -2.9909433102 +5180 53.2377867465 -2.9866510624 +5181 53.2358025259 -2.981994524 +5182 53.2341158725 -2.9770230091 +5183 53.2327446297 -2.9717891449 +5184 53.2317033022 -2.9663483163 +5185 53.2310029042 -2.9607580832 +5186 53.2306508436 -2.955077575 +5187 53.2306508436 -2.9493668694 +5188 53.2310029042 -2.9436863612 +5189 53.2317033022 -2.9380961281 +5190 53.2327446297 -2.9326552995 +5191 53.2341158725 -2.9274214353 +5192 53.2358025259 -2.9224499205 +5193 53.2377867465 -2.917793382 +5194 53.2400475405 -2.9135011342 +5195 53.2425609844 -2.9096186577 +5196 53.2453004767 -2.9061871184 +5197 53.248237018 -2.9032429302 +5198 53.2513395174 -2.9008173681 +5199 53.2545751195 -2.8989362332 +5200 53.2579095522 -2.8976195758 +5201 53.2613074885 -2.8968814782 +5202 53.26473292 -2.8967299002 +5203 53.2681495386 -2.8971665887 +5204 53.2715211209 -2.8981870536 +5205 53.2748119126 -2.8997806091 +5206 53.2779870081 -2.901930482 +5207 53.2810127215 -2.9046139839 +5208 53.2838569448 -2.9078027478 +5209 53.2864894898 -2.9114630252 +5210 53.2888824097 -2.9155560417 +5211 53.2910102972 -2.920038407 +5212 53.2928505553 -2.9248625747 +5213 53.2943836389 -2.9299773479 +5214 53.2955932635 -2.9353284246 +5215 53.2964665791 -2.9408589761 +5216 53.2969943076 -2.946510255 +5217 53.2971708423 -2.9522222222 +5218 53.8093901962 -2.8041666667 +5219 53.8092136741 -2.8099480329 +5220 53.8086859834 -2.8156679709 +5221 53.8078127308 -2.8212657095 +5222 53.8066031939 -2.8266817852 +5223 53.8050702223 -2.8318586771 +5224 53.8032301001 -2.836741422 +5225 53.8011023716 -2.8412782002 +5226 53.7987096328 -2.8454208877 +5227 53.7960772901 -2.8491255674 +5228 53.7932332887 -2.852352995 +5229 53.7902078153 -2.855069014 +5230 53.787032976 -2.857244915 +5231 53.7837424545 -2.8588577369 +5232 53.780371154 -2.859890506 +5233 53.7769548261 -2.8603324101 +5234 53.7735296912 -2.8601789083 +5235 53.7701320543 -2.8594317722 +5236 53.7667979202 -2.8580990616 +5237 53.7635626126 -2.8561950329 +5238 53.7604604 -2.8537399825 +5239 53.7575241339 -2.850760027 +5240 53.7547849019 -2.8472868223 +5241 53.7522716996 -2.8433572254 +5242 53.7500111253 -2.839012902 +5243 53.7480270994 -2.8342998842 +5244 53.7463406129 -2.8292680834 +5245 53.7449695067 -2.8239707635 +5246 53.7439282835 -2.8184639791 +5247 53.7432279559 -2.8128059857 +5248 53.7428759307 -2.807056627 +5249 53.7428759307 -2.8012767063 +5250 53.7432279559 -2.7955273476 +5251 53.7439282835 -2.7898693542 +5252 53.7449695067 -2.7843625699 +5253 53.7463406129 -2.7790652499 +5254 53.7480270994 -2.7740334492 +5255 53.7500111253 -2.7693204313 +5256 53.7522716996 -2.7649761079 +5257 53.7547849019 -2.7610465111 +5258 53.7575241339 -2.7575733064 +5259 53.7604604 -2.7545933508 +5260 53.7635626126 -2.7521383004 +5261 53.7667979202 -2.7502342717 +5262 53.7701320543 -2.7489015611 +5263 53.7735296912 -2.748154425 +5264 53.7769548261 -2.7480009232 +5265 53.780371154 -2.7484428274 +5266 53.7837424545 -2.7494755964 +5267 53.787032976 -2.7510884183 +5268 53.7902078153 -2.7532643193 +5269 53.7932332887 -2.7559803383 +5270 53.7960772901 -2.759207766 +5271 53.7987096328 -2.7629124456 +5272 53.8011023716 -2.7670551331 +5273 53.8032301001 -2.7715919114 +5274 53.8050702223 -2.7764746563 +5275 53.8066031939 -2.7816515482 +5276 53.8078127308 -2.7870676238 +5277 53.8086859834 -2.7926653624 +5278 53.8092136741 -2.7983853004 +5279 53.8093901962 -2.8041666667 +5280 53.3909816953 -0.5508333333 +5281 53.3908032038 -0.559936563 +5282 53.3902684981 -0.5690005838 +5283 53.389379881 -0.5779863586 +5284 53.3881411797 -0.5868551933 +5285 53.3865577284 -0.595568906 +5286 53.3846363454 -0.6040899938 +5287 53.382385303 -0.6123817972 +5288 53.3798142914 -0.6204086597 +5289 53.3769343765 -0.6281360829 +5290 53.3737579512 -0.6355308768 +5291 53.3702986815 -0.6425613032 +5292 53.366571447 -0.6491972133 +5293 53.3625922757 -0.6554101771 +5294 53.3583782744 -0.6611736056 +5295 53.3539475544 -0.6664628642 +5296 53.3493191525 -0.6712553778 +5297 53.3445129487 -0.6755307254 +5298 53.33954958 -0.6792707268 +5299 53.3344503507 -0.6824595172 +5300 53.3292371409 -0.6850836134 +5301 53.3239323115 -0.687131968 +5302 53.3185586082 -0.6885960136 +5303 53.3131390634 -0.6894696963 +5304 53.3076968973 -0.6897494974 +5305 53.3022554181 -0.6894344449 +5306 53.2968379224 -0.688526114 +5307 53.2914675952 -0.687028616 +5308 53.2861674113 -0.6849485775 +5309 53.2809600368 -0.6822951079 +5310 53.2758677328 -0.6790797571 +5311 53.2709122608 -0.6753164628 +5312 53.2661147902 -0.6710214883 +5313 53.2614958084 -0.6662133499 +5314 53.2570750343 -0.6609127355 +5315 53.2528713345 -0.6551424149 +5316 53.2489026439 -0.6489271405 +5317 53.2451858903 -0.6422935407 +5318 53.2417369221 -0.6352700061 +5319 53.2385704427 -0.6278865676 +5320 53.235699948 -0.6201747691 +5321 53.2331376696 -0.6121675334 +5322 53.230894524 -0.6038990228 +5323 53.2289800663 -0.5954044954 +5324 53.2274024504 -0.5867201563 +5325 53.2261683946 -0.5778830057 +5326 53.2252831538 -0.5689306834 +5327 53.2247504972 -0.5599013112 +5328 53.2245726926 -0.5508333333 +5329 53.2247504972 -0.5417653554 +5330 53.2252831538 -0.5327359832 +5331 53.2261683946 -0.5237836609 +5332 53.2274024504 -0.5149465103 +5333 53.2289800663 -0.5062621713 +5334 53.230894524 -0.4977676439 +5335 53.2331376696 -0.4894991333 +5336 53.235699948 -0.4814918975 +5337 53.2385704427 -0.473780099 +5338 53.2417369221 -0.4663966606 +5339 53.2451858903 -0.459373126 +5340 53.2489026439 -0.4527395262 +5341 53.2528713345 -0.4465242517 +5342 53.2570750343 -0.4407539311 +5343 53.2614958084 -0.4354533168 +5344 53.2661147902 -0.4306451783 +5345 53.2709122608 -0.4263502038 +5346 53.2758677328 -0.4225869096 +5347 53.2809600368 -0.4193715588 +5348 53.2861674113 -0.4167180891 +5349 53.2914675952 -0.4146380506 +5350 53.2968379224 -0.4131405527 +5351 53.3022554181 -0.4122322218 +5352 53.3076968973 -0.4119171693 +5353 53.3131390634 -0.4121969703 +5354 53.3185586082 -0.413070653 +5355 53.3239323115 -0.4145346987 +5356 53.3292371409 -0.4165830533 +5357 53.3344503507 -0.4192071494 +5358 53.33954958 -0.4223959399 +5359 53.3445129487 -0.4261359412 +5360 53.3493191525 -0.4304112889 +5361 53.3539475544 -0.4352038024 +5362 53.3583782744 -0.4404930611 +5363 53.3625922757 -0.4462564895 +5364 53.366571447 -0.4524694533 +5365 53.3702986815 -0.4591053634 +5366 53.3737579512 -0.4661357899 +5367 53.3769343765 -0.4735305838 +5368 53.3798142914 -0.481258007 +5369 53.382385303 -0.4892848694 +5370 53.3846363454 -0.4975766729 +5371 53.3865577284 -0.5060977607 +5372 53.3881411797 -0.5148114733 +5373 53.389379881 -0.5236803081 +5374 53.3902684981 -0.5326660829 +5375 53.3908032038 -0.5417301037 +5376 53.3909816953 -0.5508333333 +5377 53.4493672106 -4.4812194444 +5378 53.4491906797 -4.4869518094 +5379 53.4486629624 -4.4926232685 +5380 53.4477896656 -4.4981735678 +5381 53.4465800672 -4.5035437489 +5382 53.445047017 -4.5086767801 +5383 53.4432067994 -4.5135181648 +5384 53.4410789594 -4.5180165232 +5385 53.4386860935 -4.5221241391 +5386 53.4360536087 -4.5257974674 +5387 53.4332094516 -4.5289975955 +5388 53.4301838097 -4.531690655 +5389 53.4270087905 -4.5338481782 +5390 53.4237180793 -4.5354473967 +5391 53.4203465809 -4.5364714781 +5392 53.4169300489 -4.5369096997 +5393 53.4135047057 -4.5367575564 +5394 53.4101068585 -4.5360168024 +5395 53.4067725146 -4.5346954268 +5396 53.4035370001 -4.532807563 +5397 53.4004345861 -4.5303733337 +5398 53.3974981266 -4.5274186328 +5399 53.3947587118 -4.5239748471 +5400 53.3922453397 -4.5200785209 +5401 53.389984611 -4.5157709669 +5402 53.3880004483 -4.5110978279 +5403 53.3863138446 -4.5061085937 +5404 53.3849426423 -4.5008560783 +5405 53.3839013458 -4.4953958637 +5406 53.3832009688 -4.4897857142 +5407 53.3828489187 -4.4840849692 +5408 53.3828489187 -4.4783539196 +5409 53.3832009688 -4.4726531746 +5410 53.3839013458 -4.4670430252 +5411 53.3849426423 -4.4615828106 +5412 53.3863138446 -4.4563302952 +5413 53.3880004483 -4.451341061 +5414 53.389984611 -4.4466679219 +5415 53.3922453397 -4.442360368 +5416 53.3947587118 -4.4384640418 +5417 53.3974981266 -4.4350202561 +5418 53.4004345861 -4.4320655552 +5419 53.4035370001 -4.4296313259 +5420 53.4067725146 -4.4277434621 +5421 53.4101068585 -4.4264220865 +5422 53.4135047057 -4.4256813325 +5423 53.4169300489 -4.4255291891 +5424 53.4203465809 -4.4259674108 +5425 53.4237180793 -4.4269914922 +5426 53.4270087905 -4.4285907107 +5427 53.4301838097 -4.4307482339 +5428 53.4332094516 -4.4334412934 +5429 53.4360536087 -4.4366414215 +5430 53.4386860935 -4.4403147498 +5431 53.4410789594 -4.4444223657 +5432 53.4432067994 -4.4489207241 +5433 53.445047017 -4.4537621088 +5434 53.4465800672 -4.45889514 +5435 53.4477896656 -4.4642653211 +5436 53.4486629624 -4.4698156203 +5437 53.4491906797 -4.4754870795 +5438 53.4493672106 -4.4812194444 +5439 54.451331069 -3.4955555556 +5440 54.4511545625 -3.5014269937 +5441 54.4506269186 -3.5072360431 +5442 54.4497537438 -3.5129209825 +5443 54.4485443153 -3.5184214188 +5444 54.4470114824 -3.5236789329 +5445 54.4451715284 -3.5286377032 +5446 54.4430439969 -3.5332451019 +5447 54.4406514827 -3.537452255 +5448 54.4380193906 -3.5412145619 +5449 54.4351756646 -3.5444921685 +5450 54.4321504892 -3.5472503885 +5451 54.4289759681 -3.5494600685 +5452 54.4256857826 -3.5510978936 +5453 54.4223148326 -3.5521466295 +5454 54.4188988665 -3.5525953007 +5455 54.415474101 -3.5524392998 +5456 54.4120768371 -3.551680431 +5457 54.4087430754 -3.5503268838 +5458 54.4055081352 -3.5483931406 +5459 54.4024062804 -3.5458998173 +5460 54.399470358 -3.54287344 +5461 54.3967314511 -3.5393461593 +5462 54.3942185508 -3.535355407 +5463 54.3919582512 -3.5309434975 +5464 54.3899744688 -3.5261571785 +5465 54.388288191 -3.5210471366 +5466 54.3869172556 -3.5156674621 +5467 54.3858761629 -3.5100750787 +5468 54.3851759235 -3.5043291446 +5469 54.3848239427 -3.4984904303 +5470 54.3848239427 -3.4926206808 +5471 54.3851759235 -3.4867819665 +5472 54.3858761629 -3.4810360324 +5473 54.3869172556 -3.475443649 +5474 54.388288191 -3.4700639745 +5475 54.3899744688 -3.4649539326 +5476 54.3919582512 -3.4601676136 +5477 54.3942185508 -3.4557557041 +5478 54.3967314511 -3.4517649518 +5479 54.399470358 -3.4482376711 +5480 54.4024062804 -3.4452112938 +5481 54.4055081352 -3.4427179705 +5482 54.4087430754 -3.4407842274 +5483 54.4120768371 -3.4394306801 +5484 54.415474101 -3.4386718113 +5485 54.4188988665 -3.4385158104 +5486 54.4223148326 -3.4389644816 +5487 54.4256857826 -3.4400132175 +5488 54.4289759681 -3.4416510426 +5489 54.4321504892 -3.4438607226 +5490 54.4351756646 -3.4466189426 +5491 54.4380193906 -3.4498965493 +5492 54.4406514827 -3.4536588561 +5493 54.4430439969 -3.4578660092 +5494 54.4451715284 -3.4624734079 +5495 54.4470114824 -3.4674321783 +5496 54.4485443153 -3.4726896923 +5497 54.4497537438 -3.4781901287 +5498 54.4506269186 -3.483875068 +5499 54.4511545625 -3.4896841174 +5500 54.451331069 -3.4955555556 +5501 54.0630915593 -2.9144222222 +5502 54.0629150434 -2.9202387654 +5503 54.0623873713 -2.9259935051 +5504 54.0615141495 -2.9316252994 +5505 54.0603046557 -2.9370743215 +5506 54.0587717391 -2.9422826999 +5507 54.0569316837 -2.9471951361 +5508 54.0548040333 -2.9517594948 +5509 54.0524113837 -2.955927359 +5510 54.0497791404 -2.9596545448 +5511 54.0469352482 -2.9629015698 +5512 54.0439098929 -2.9656340704 +5513 54.0407351798 -2.9678231638 +5514 54.0374447914 -2.9694457509 +5515 54.0340736299 -2.970484756 +5516 54.0306574453 -2.9709293033 +5517 54.0272324567 -2.9707748258 +5518 54.0238349675 -2.9700231078 +5519 54.0205009808 -2.9686822598 +5520 54.0172658186 -2.9667666265 +5521 54.0141637476 -2.9642966289 +5522 54.0112276176 -2.9612985437 +5523 54.0084885142 -2.9578042199 +5524 54.0059754314 -2.9538507391 +5525 54.0037149657 -2.9494800202 +5526 54.0017310361 -2.9447383748 +5527 54.0000446322 -2.9396760171 +5528 53.9986735935 -2.9343465338 +5529 53.9976324219 -2.9288063188 +5530 53.9969321292 -2.9231139803 +5531 53.9965801216 -2.9173297239 +5532 53.9965801216 -2.9115147206 +5533 53.9969321292 -2.9057304642 +5534 53.9976324219 -2.9000381256 +5535 53.9986735935 -2.8944979107 +5536 54.0000446322 -2.8891684273 +5537 54.0017310361 -2.8841060697 +5538 54.0037149657 -2.8793644243 +5539 54.0059754314 -2.8749937053 +5540 54.0084885142 -2.8710402245 +5541 54.0112276176 -2.8675459008 +5542 54.0141637476 -2.8645478155 +5543 54.0172658186 -2.862077818 +5544 54.0205009808 -2.8601621846 +5545 54.0238349675 -2.8588213367 +5546 54.0272324567 -2.8580696187 +5547 54.0306574453 -2.8579151412 +5548 54.0340736299 -2.8583596884 +5549 54.0374447914 -2.8593986936 +5550 54.0407351798 -2.8610212806 +5551 54.0439098929 -2.8632103741 +5552 54.0469352482 -2.8659428747 +5553 54.0497791404 -2.8691898996 +5554 54.0524113837 -2.8729170854 +5555 54.0548040333 -2.8770849496 +5556 54.0569316837 -2.8816493083 +5557 54.0587717391 -2.8865617445 +5558 54.0603046557 -2.8917701229 +5559 54.0615141495 -2.897219145 +5560 54.0623873713 -2.9028509393 +5561 54.0629150434 -2.908605679 +5562 54.0630915593 -2.9144222222 +5563 54.118041546 -3.2361111111 +5564 54.1178712153 -3.2389617203 +5565 54.1173672007 -3.2416955575 +5566 54.1165501481 -3.2442006422 +5567 54.1154535248 -3.2463743796 +5568 54.1141222467 -3.248127766 +5569 54.112610836 -3.249389035 +5570 54.110981186 -3.2501065925 +5571 54.1093000245 -3.250251122 +5572 54.1076361805 -3.2498167752 +5573 54.1060577659 -3.2488214002 +5574 54.104629388 -3.2473058003 +5575 54.1034095068 -3.2453320547 +5576 54.1024480441 -3.2429809723 +5577 54.1017843434 -3.2403487825 +5578 54.1014455622 -3.2375432 +5579 54.1014455622 -3.2346790222 +5580 54.1017843434 -3.2318734397 +5581 54.1024480441 -3.2292412499 +5582 54.1034095068 -3.2268901675 +5583 54.104629388 -3.2249164219 +5584 54.1060577659 -3.223400822 +5585 54.1076361805 -3.2224054471 +5586 54.1093000245 -3.2219711003 +5587 54.110981186 -3.2221156297 +5588 54.112610836 -3.2228331872 +5589 54.1141222467 -3.2240944562 +5590 54.1154535248 -3.2258478426 +5591 54.1165501481 -3.22802158 +5592 54.1173672007 -3.2305266648 +5593 54.1178712153 -3.2332605019 +5594 54.118041546 -3.2361111111 +5595 54.6685520888 -1.1802777778 +5596 54.6683755875 -1.1861805046 +5597 54.6678479593 -1.192020509 +5598 54.6669748105 -1.1977357397 +5599 54.6657654184 -1.2032654807 +5600 54.6642326319 -1.2085510006 +5601 54.6623927343 -1.2135361801 +5602 54.6602652688 -1.2181681102 +5603 54.6578728299 -1.2223976566 +5604 54.655240822 -1.2261799812 +5605 54.6523971884 -1.2294750182 +5606 54.649372113 -1.2322478972 +5607 54.646197699 -1.2344693105 +5608 54.6429076263 -1.2361158203 +5609 54.6395367943 -1.2371701022 +5610 54.63612095 -1.2376211234 +5611 54.6326963088 -1.2374642539 +5612 54.6292991706 -1.2367013088 +5613 54.6259655344 -1.2353405231 +5614 54.622730718 -1.2333964576 +5615 54.6196289839 -1.2308898392 +5616 54.6166931775 -1.2278473362 +5617 54.6139543803 -1.224301271 +5618 54.611441582 -1.2202892752 +5619 54.6091813752 -1.2158538885 +5620 54.607197675 -1.2110421072 +5621 54.6055114677 -1.2059048872 +5622 54.6041405901 -1.2004966058 +5623 54.6030995414 -1.1948744885 +5624 54.6023993318 -1.189098007 +5625 54.602047366 -1.1832282541 +5626 54.602047366 -1.1773273015 +5627 54.6023993318 -1.1714575485 +5628 54.6030995414 -1.1656810671 +5629 54.6041405901 -1.1600589498 +5630 54.6055114677 -1.1546506683 +5631 54.607197675 -1.1495134483 +5632 54.6091813752 -1.144701667 +5633 54.611441582 -1.1402662803 +5634 54.6139543803 -1.1362542845 +5635 54.6166931775 -1.1327082194 +5636 54.6196289839 -1.1296657163 +5637 54.622730718 -1.127159098 +5638 54.6259655344 -1.1252150324 +5639 54.6292991706 -1.1238542467 +5640 54.6326963088 -1.1230913017 +5641 54.63612095 -1.1229344322 +5642 54.6395367943 -1.1233854534 +5643 54.6429076263 -1.1244397352 +5644 54.646197699 -1.126086245 +5645 54.649372113 -1.1283076584 +5646 54.6523971884 -1.1310805374 +5647 54.655240822 -1.1343755744 +5648 54.6578728299 -1.138157899 +5649 54.6602652688 -1.1423874453 +5650 54.6623927343 -1.1470193755 +5651 54.6642326319 -1.1520045549 +5652 54.6657654184 -1.1572900749 +5653 54.6669748105 -1.1628198159 +5654 54.6678479593 -1.1685350466 +5655 54.6683755875 -1.1743750509 +5656 54.6685520888 -1.1802777778 +5657 55.7546572369 -4.8938888889 +5658 55.7544807614 -4.8999545473 +5659 55.7539532102 -4.9059557454 +5660 55.7530801894 -4.9118287131 +5661 55.751870976 -4.9175110532 +5662 55.7503384181 -4.9229424086 +5663 55.748498798 -4.9280651075 +5664 55.7463716576 -4.9328247789 +5665 55.7439795898 -4.9371709319 +5666 55.7413479969 -4.941057492 +5667 55.7385048196 -4.9444432906 +5668 55.7354802387 -4.9472924991 +5669 55.7323063534 -4.9495750068 +5670 55.7290168396 -4.9512667358 +5671 55.7256465915 -4.9523498915 +5672 55.7222313507 -4.9528131451 +5673 55.7188073265 -4.9526517473 +5674 55.7154108119 -4.9518675721 +5675 55.7120777991 -4.9504690896 +5676 55.7088435984 -4.9484712699 +5677 55.7057424646 -4.9458954179 +5678 55.7028072354 -4.9427689426 +5679 55.7000689844 -4.9391250617 +5680 55.697556694 -4.9350024464 +5681 55.6952969494 -4.9304448098 +5682 55.6933136592 -4.9255004428 +5683 55.6916278036 -4.9202217032 +5684 55.6902572139 -4.9146644628 +5685 55.6892163852 -4.908887519 +5686 55.6885163242 -4.9029519762 +5687 55.6881644332 -4.8969206031 +5688 55.6881644332 -4.8908571746 +5689 55.6885163242 -4.8848258016 +5690 55.6892163852 -4.8788902587 +5691 55.6902572139 -4.873113315 +5692 55.6916278036 -4.8675560746 +5693 55.6933136592 -4.862277335 +5694 55.6952969494 -4.8573329679 +5695 55.697556694 -4.8527753314 +5696 55.7000689844 -4.8486527161 +5697 55.7028072354 -4.8450088351 +5698 55.7057424646 -4.8418823598 +5699 55.7088435984 -4.8393065079 +5700 55.7120777991 -4.8373086881 +5701 55.7154108119 -4.8359102057 +5702 55.7188073265 -4.8351260305 +5703 55.7222313507 -4.8349646327 +5704 55.7256465915 -4.8354278863 +5705 55.7290168396 -4.836511042 +5706 55.7323063534 -4.838202771 +5707 55.7354802387 -4.8404852787 +5708 55.7385048196 -4.8433344872 +5709 55.7413479969 -4.8467202857 +5710 55.7439795898 -4.8506068459 +5711 55.7463716576 -4.8549529988 +5712 55.748498798 -4.8597126703 +5713 55.7503384181 -4.8648353692 +5714 55.751870976 -4.8702667246 +5715 55.7530801894 -4.8759490647 +5716 55.7539532102 -4.8818220324 +5717 55.7544807614 -4.8878232305 +5718 55.7546572369 -4.8938888889 +5719 56.0015392269 -2.4084777778 +5720 56.0013627571 -2.4145820483 +5721 56.0008352231 -2.4206214466 +5722 55.9999622309 -2.4265317954 +5723 55.9987530573 -2.4322502988 +5724 55.9972205504 -2.4377162144 +5725 55.9953809923 -2.4428715028 +5726 55.9932539246 -2.4476614461 +5727 55.9908619399 -2.4520352321 +5728 55.98823044 -2.4559464934 +5729 55.985387365 -2.4593537998 +5730 55.982362895 -2.4622210959 +5731 55.9791891284 -2.4645180807 +5732 55.9758997402 -2.4662205246 +5733 55.9725296235 -2.4673105215 +5734 55.9691145185 -2.4677766727 +5735 55.9656906333 -2.4676142006 +5736 55.9622942594 -2.4668249932 +5737 55.9589613873 -2.4654175764 +5738 55.9557273257 -2.4634070172 +5739 55.9526263276 -2.4608147578 +5740 55.9496912288 -2.4576683825 +5741 55.9469531015 -2.4540013212 +5742 55.9444409261 -2.4498524916 +5743 55.9421812862 -2.4452658848 +5744 55.9401980889 -2.4402900985 +5745 55.938512313 -2.4349778227 +5746 55.9371417886 -2.4293852834 +5747 55.9361010098 -2.4235716504 +5748 55.9354009824 -2.4175984149 +5749 55.9350491084 -2.4115287429 +5750 55.9350491084 -2.4054268127 +5751 55.9354009824 -2.3993571407 +5752 55.9361010098 -2.3933839051 +5753 55.9371417886 -2.3875702722 +5754 55.938512313 -2.3819777329 +5755 55.9401980889 -2.376665457 +5756 55.9421812862 -2.3716896707 +5757 55.9444409261 -2.367103064 +5758 55.9469531015 -2.3629542344 +5759 55.9496912288 -2.3592871731 +5760 55.9526263276 -2.3561407978 +5761 55.9557273257 -2.3535485383 +5762 55.9589613873 -2.3515379792 +5763 55.9622942594 -2.3501305624 +5764 55.9656906333 -2.3493413549 +5765 55.9691145185 -2.3491788829 +5766 55.9725296235 -2.3496450341 +5767 55.9758997402 -2.350735031 +5768 55.9791891284 -2.3524374749 +5769 55.982362895 -2.3547344596 +5770 55.985387365 -2.3576017558 +5771 55.98823044 -2.3610090622 +5772 55.9908619399 -2.3649203235 +5773 55.9932539246 -2.3692941094 +5774 55.9953809923 -2.3740840528 +5775 55.9972205504 -2.3792393411 +5776 55.9987530573 -2.3847052568 +5777 55.9999622309 -2.3904237602 +5778 56.0008352231 -2.3963341089 +5779 56.0013627571 -2.4023735073 +5780 56.0015392269 -2.4084777778 +5781 56.0380389069 -3.4508333333 +5782 56.0378686278 -3.4538238226 +5783 56.0373647659 -3.4566918046 +5784 56.036547962 -3.4593197998 +5785 56.0354516743 -3.4616001767 +5786 56.0341208066 -3.4634395644 +5787 56.0326098656 -3.464762678 +5788 56.0309807265 -3.4655153966 +5789 56.0293000971 -3.4656669719 +5790 56.0276367846 -3.465211276 +5791 56.0260588788 -3.4641670394 +5792 56.0246309652 -3.4625770722 +5793 56.0234114834 -3.4605065022 +5794 56.0224503374 -3.4580401027 +5795 56.0217868563 -3.4552788212 +5796 56.0214481874 -3.4523356513 +5797 56.0214481874 -3.4493310153 +5798 56.0217868563 -3.4463878455 +5799 56.0224503374 -3.443626564 +5800 56.0234114834 -3.4411601645 +5801 56.0246309652 -3.4390895945 +5802 56.0260588788 -3.4374996273 +5803 56.0276367846 -3.4364553907 +5804 56.0293000971 -3.4359996948 +5805 56.0309807265 -3.4361512701 +5806 56.0326098656 -3.4369039887 +5807 56.0341208066 -3.4382271022 +5808 56.0354516743 -3.44006649 +5809 56.036547962 -3.4423468668 +5810 56.0373647659 -3.4449748621 +5811 56.0378686278 -3.447842844 +5812 56.0380389069 -3.4508333333 +5813 58.5 -3.6505555556 +5814 58.5 -4.3333333333 +5815 58.4166666667 -4.5 +5816 58.5 -4.5 +5817 58.5 -4.8166666667 +5818 58.0 -5.25 +5819 57.8333333333 -5.7166666667 +5820 57.2166666667 -5.5833333333 +5821 56.9333333333 -5.7833333333 +5822 56.9 -5.0833333333 +5823 57.0 -5.0333333333 +5824 57.15 -5.0 +5825 57.1833333333 -4.8833333333 +5826 57.3 -4.8666666667 +5827 57.5 -4.6333333333 +5828 57.6333333333 -4.75 +5829 57.65 -4.5 +5830 57.7833333333 -4.4166666667 +5831 58.0 -4.6166666667 +5832 58.05 -4.5 +5833 58.0625 -4.2133333333 +5834 58.39885 -3.4798583333 +5835 58.4744444444 -3.6375 +5836 58.5 -3.6505555556 +5837 57.8333333333 -5.7166666667 +5838 57.7875 -6.2769444444 +5839 57.0 -6.2511111111 +5840 57.0 -5.9455555556 +5841 57.6444444444 -5.9608333333 +5842 57.6677777778 -5.6805555556 +5843 57.8333333333 -5.7166666667 +5844 58.3716666667 -3.54 +5845 58.3166666667 -3.6611111111 +5846 58.1891666667 -3.4483333333 +5847 58.2427777778 -3.3247222222 +5848 58.3716666667 -3.54 +5849 57.8166666667 -4.1016666667 +5850 57.7833333333 -4.4166666667 +5851 57.65 -4.5 +5852 57.7094444444 -4.1822222222 +5853 57.75 -4.0483333333 +5854 57.8166666667 -4.1016666667 +5855 57.0574639676 -3.2302777778 +5856 57.0572866625 -3.2347217264 +5857 57.0567585311 -3.2390708352 +5858 57.0558908441 -3.2432322962 +5859 57.0547021176 -3.2471173212 +5860 57.0532177164 -3.250643042 +5861 57.0514693109 -3.2537342822 +5862 57.0494941996 -3.2563251621 +5863 57.0473345108 -3.2583605024 +5864 57.0450363023 -3.2597969969 +5865 57.0426485773 -3.260604129 +5866 57.0402222381 -3.2607648138 +5867 57.0378090004 -3.2602757524 +5868 57.0354602907 -3.2591474911 +5869 57.033226151 -3.2574041866 +5870 57.0311541735 -3.2550830817 +5871 57.0292884884 -3.2522337042 +5872 57.027668826 -3.2489168064 +5873 57.0263296728 -3.2452030682 +5874 57.025299539 -3.2411715924 +5875 57.0246003539 -3.2369082222 +5876 57.0242470008 -3.232503719 +5877 57.0242470008 -3.2280518366 +5878 57.0246003539 -3.2236473334 +5879 57.025299539 -3.2193839632 +5880 57.0263296728 -3.2153524873 +5881 57.027668826 -3.2116387492 +5882 57.0292884884 -3.2083218513 +5883 57.0311541735 -3.2054724739 +5884 57.033226151 -3.203151369 +5885 57.0354602907 -3.2014080645 +5886 57.0378090004 -3.2002798032 +5887 57.0402222381 -3.1997907417 +5888 57.0426485773 -3.1999514266 +5889 57.0450363023 -3.2007585587 +5890 57.0473345108 -3.2021950531 +5891 57.0494941996 -3.2042303935 +5892 57.0514693109 -3.2068212734 +5893 57.0532177164 -3.2099125136 +5894 57.0547021176 -3.2134382344 +5895 57.0558908441 -3.2173232594 +5896 57.0567585311 -3.2214847204 +5897 57.0572866625 -3.2258338292 +5898 57.0574639676 -3.2302777778 +5899 57.0455195551 -3.0741666667 +5900 57.0453422497 -3.078609189 +5901 57.0448141174 -3.0829569019 +5902 57.0439464289 -3.0871170275 +5903 57.0427577003 -3.0910008059 +5904 57.0412732965 -3.0945253956 +5905 57.0395248879 -3.0976156443 +5906 57.037549773 -3.1002056935 +5907 57.0353900803 -3.1022403815 +5908 57.0330918675 -3.1036764159 +5909 57.030704138 -3.10448329 +5910 57.0282777942 -3.1046439242 +5911 57.0258645518 -3.1041550205 +5912 57.0235158375 -3.1030271218 +5913 57.0212816933 -3.1012843771 +5914 57.0192097116 -3.0989640172 +5915 57.0173440227 -3.0961155538 +5916 57.0157243569 -3.0927997198 +5917 57.0143852009 -3.0890871725 +5918 57.0133550649 -3.0850569891 +5919 57.0126558784 -3.0807949857 +5920 57.0123025245 -3.0763918943 +5921 57.0123025245 -3.071941439 +5922 57.0126558784 -3.0675383477 +5923 57.0133550649 -3.0632763442 +5924 57.0143852009 -3.0592461609 +5925 57.0157243569 -3.0555336136 +5926 57.0173440227 -3.0522177795 +5927 57.0192097116 -3.0493693162 +5928 57.0212816933 -3.0470489562 +5929 57.0235158375 -3.0453062115 +5930 57.0258645518 -3.0441783129 +5931 57.0282777942 -3.0436894092 +5932 57.030704138 -3.0438500434 +5933 57.0330918675 -3.0446569174 +5934 57.0353900803 -3.0460929518 +5935 57.037549773 -3.0481276399 +5936 57.0395248879 -3.050717689 +5937 57.0412732965 -3.0538079377 +5938 57.0427577003 -3.0573325274 +5939 57.0439464289 -3.0612163059 +5940 57.0448141174 -3.0653764314 +5941 57.0453422497 -3.0697241443 +5942 57.0455195551 -3.0741666667 +5943 50.1360027382 -5.6705805556 +5944 50.1358261226 -5.6759075942 +5945 50.135298152 -5.6811780483 +5946 50.1344244342 -5.6863359382 +5947 50.1332142493 -5.691326487 +5948 50.1316804503 -5.6960967056 +5949 50.1298393258 -5.7005959583 +5950 50.1277104258 -5.7047765024 +5951 50.1253163537 -5.7085939962 +5952 50.1226825245 -5.7120079707 +5953 50.1198368943 -5.714982258 +5954 50.1168096619 -5.7174853742 +5955 50.1136329477 -5.7194908511 +5956 50.1103404517 -5.7209775143 +5957 50.1069670951 -5.7219297036 +5958 50.1035486495 -5.7223374351 +5959 50.1001213569 -5.7221965023 +5960 50.0967215454 -5.7215085159 +5961 50.0933852444 -5.7202808818 +5962 50.0901478028 -5.7185267176 +5963 50.087043515 -5.7162647094 +5964 50.0841052587 -5.7135189097 +5965 50.0813641471 -5.7103184794 +5966 50.078849201 -5.7066973762 +5967 50.0765870422 -5.7026939937 +5968 50.0746016133 -5.6983507534 +5969 50.0729139251 -5.6937136564 +5970 50.0715418357 -5.6888317968 +5971 50.0704998622 -5.6837568442 +5972 50.0697990282 -5.6785424991 +5973 50.0694467479 -5.6732439281 +5974 50.0694467479 -5.667917183 +5975 50.0697990282 -5.662618612 +5976 50.0704998622 -5.6574042669 +5977 50.0715418357 -5.6523293143 +5978 50.0729139251 -5.6474474547 +5979 50.0746016133 -5.6428103577 +5980 50.0765870422 -5.6384671174 +5981 50.078849201 -5.6344637349 +5982 50.0813641471 -5.6308426317 +5983 50.0841052587 -5.6276422014 +5984 50.087043515 -5.6248964017 +5985 50.0901478028 -5.6226343935 +5986 50.0933852444 -5.6208802293 +5987 50.0967215454 -5.6196525952 +5988 50.1001213569 -5.6189646089 +5989 50.1035486495 -5.6188236761 +5990 50.1069670951 -5.6192314075 +5991 50.1103404517 -5.6201835968 +5992 50.1136329477 -5.62167026 +5993 50.1168096619 -5.6236757369 +5994 50.1198368943 -5.6261788531 +5995 50.1226825245 -5.6291531404 +5996 50.1253163537 -5.6325671149 +5997 50.1277104258 -5.6363846088 +5998 50.1298393258 -5.6405651528 +5999 50.1316804503 -5.6450644055 +6000 50.1332142493 -5.6498346241 +6001 50.1344244342 -5.6548251729 +6002 50.135298152 -5.6599830628 +6003 50.1358261226 -5.6652535169 +6004 50.1360027382 -5.6705805556 +6005 50.0572722222 -5.6911472222 +6006 50.0705099722 -5.6838163611 +6007 50.0714098034 -5.688277731 +6008 50.072565022 -5.6925948678 +6009 50.0739661944 -5.6967325833 +6010 50.0602944444 -5.7043 +6011 50.0572722222 -5.6911472222 +6012 50.1487388889 -5.6552638889 +6013 50.135601 -5.6625601111 +6014 50.1350009132 -5.6579724056 +6015 50.1341368825 -5.6534878727 +6016 50.133016 -5.6491431944 +6017 50.1457166667 -5.6420861111 +6018 50.1487388889 -5.6552638889 +6019 50.0781908333 -5.7388095556 +6020 50.0854752222 -5.7148789444 +6021 50.0881153518 -5.7171147379 +6022 50.0908744357 -5.7189715321 +6023 50.09373 -5.7204341389 +6024 50.0863204167 -5.7447753056 +6025 50.0781908333 -5.7388095556 +6026 50.1271384722 -5.6103814444 +6027 50.1217638889 -5.6281196944 +6028 50.1192229179 -5.6256200098 +6029 50.1165472972 -5.6234872223 +6030 50.1137588611 -5.6217386667 +6031 50.1190089444 -5.6044106111 +6032 50.1271384722 -5.6103814444 +6033 50.1157045 -5.7417068611 +6034 50.1101511389 -5.7210458611 +6035 50.1130486781 -5.7197968384 +6036 50.1158619309 -5.7181462876 +6037 50.1185679444 -5.7161076111 +6038 50.1239965556 -5.7363042222 +6039 50.1157045 -5.7417068611 +6040 50.0878068333 -5.6019960278 +6041 50.0929611389 -5.6210773611 +6042 50.0901288342 -5.6226464125 +6043 50.087399098 -5.6246059681 +6044 50.0847941667 -5.62694 +6045 50.0795147222 -5.6073946111 +6046 50.0878068333 -5.6019960278 +6047 50.1452111111 -5.704525 +6048 50.1316766111 -5.6961072222 +6049 50.1330387019 -5.6919400848 +6050 50.1341536005 -5.6875986663 +6051 50.1350122222 -5.6831183889 +6052 50.1485444444 -5.6915305556 +6053 50.1452111111 -5.704525 +6054 50.0593444444 -5.636175 +6055 50.0737236667 -5.6450833611 +6056 50.0723633887 -5.649245904 +6057 50.0712499565 -5.653581799 +6058 50.0703924167 -5.6580558056 +6059 50.0560111111 -5.6491416667 +6060 50.0593444444 -5.636175 +6061 50.1636886897 -5.5139555556 +6062 50.1635120748 -5.5192856706 +6063 50.1629841063 -5.5245591683 +6064 50.1621103922 -5.5297200365 +6065 50.1609002124 -5.5347134667 +6066 50.1593664198 -5.539486439 +6067 50.157525303 -5.5439882886 +6068 50.1553964121 -5.5481712449 +6069 50.1530023503 -5.5519909409 +6070 50.1503685326 -5.555406884 +6071 50.1475229149 -5.5583828855 +6072 50.1444956961 -5.5608874435 +6073 50.1413189963 -5.5628940747 +6074 50.1380265155 -5.5643815924 +6075 50.1346531747 -5.5653343275 +6076 50.1312347453 -5.5657422906 +6077 50.1278074691 -5.5656012729 +6078 50.1244076743 -5.5649128862 +6079 50.1210713898 -5.5636845407 +6080 50.1178339644 -5.5619293619 +6081 50.1147296924 -5.5596660466 +6082 50.1117914512 -5.5569186613 +6083 50.1090503539 -5.5537163839 +6084 50.106535421 -5.5500931917 +6085 50.1042732742 -5.5460875004 +6086 50.1022878559 -5.541741756 +6087 50.1006001768 -5.5371019861 +6088 50.0992280948 -5.532217313 +6089 50.098186127 -5.5271394359 +6090 50.0974852968 -5.5219220864 +6091 50.0971330184 -5.5166204626 +6092 50.0971330184 -5.5112906485 +6093 50.0974852968 -5.5059890247 +6094 50.098186127 -5.5007716752 +6095 50.0992280948 -5.4956937982 +6096 50.1006001768 -5.490809125 +6097 50.1022878559 -5.4861693551 +6098 50.1042732742 -5.4818236107 +6099 50.106535421 -5.4778179194 +6100 50.1090503539 -5.4741947272 +6101 50.1117914512 -5.4709924498 +6102 50.1147296924 -5.4682450646 +6103 50.1178339644 -5.4659817493 +6104 50.1210713898 -5.4642265704 +6105 50.1244076743 -5.4629982249 +6106 50.1278074691 -5.4623098382 +6107 50.1312347453 -5.4621688205 +6108 50.1346531747 -5.4625767836 +6109 50.1380265155 -5.4635295187 +6110 50.1413189963 -5.4650170364 +6111 50.1444956961 -5.4670236676 +6112 50.1475229149 -5.4695282256 +6113 50.1503685326 -5.4725042271 +6114 50.1530023503 -5.4759201702 +6115 50.1553964121 -5.4797398662 +6116 50.157525303 -5.4839228226 +6117 50.1593664198 -5.4884246721 +6118 50.1609002124 -5.4931976444 +6119 50.1621103922 -5.4981910746 +6120 50.1629841063 -5.5033519428 +6121 50.1635120748 -5.5086254405 +6122 50.1636886897 -5.5139555556 +6123 50.118266 -5.5817965278 +6124 50.1203276389 -5.5633322778 +6125 50.1232299001 -5.5645434783 +6126 50.1261905351 -5.5653429327 +6127 50.1291854444 -5.5657240556 +6128 50.1271248889 -5.58417825 +6129 50.118266 -5.5817965278 +6130 50.1424680556 -5.4460903889 +6131 50.1404263056 -5.46455675 +6132 50.1375229498 -5.4633515891 +6133 50.1345615865 -5.4625586488 +6134 50.1315663333 -5.4621843333 +6135 50.1336091944 -5.4437078889 +6136 50.1424680556 -5.4460903889 +6137 50.1270222675 -5.2540722222 +6138 50.1268445494 -5.2600465019 +6139 50.1263129153 -5.2659696794 +6140 50.1254319124 -5.271791093 +6141 50.124209076 -5.2774609581 +6142 50.1226548643 -5.282930796 +6143 50.1207825685 -5.2881538508 +6144 50.1186081982 -5.293085492 +6145 50.1161503437 -5.2976835968 +6146 50.1134300161 -5.3019089119 +6147 50.1104704664 -5.3057253884 +6148 50.1072969857 -5.3091004903 +6149 50.1039366885 -5.3120054703 +6150 50.1004182793 -5.3144156139 +6151 50.0967718071 -5.3163104478 +6152 50.0930284076 -5.3176739117 +6153 50.0892200368 -5.3184944912 +6154 50.0853791979 -5.3187653125 +6155 50.0815386634 -5.3184841965 +6156 50.0777311953 -5.3176536728 +6157 50.073989266 -5.316280954 +6158 50.0703447816 -5.3143778694 +6159 50.06682881 -5.3119607606 +6160 50.0634713172 -5.3090503379 +6161 50.0603009122 -5.3056715012 +6162 50.0573446048 -5.3018531249 +6163 50.0546275756 -5.2976278098 +6164 50.0521729635 -5.2930316047 +6165 50.0500016689 -5.2881036984 +6166 50.0481321775 -5.2828860862 +6167 50.0465804034 -5.2774232136 +6168 50.0453595547 -5.271761599 +6169 50.0444800221 -5.2659494404 +6170 50.0439492907 -5.2600362071 +6171 50.0437718769 -5.2540722222 +6172 50.0439492907 -5.2481082373 +6173 50.0444800221 -5.242195004 +6174 50.0453595547 -5.2363828454 +6175 50.0465804034 -5.2307212309 +6176 50.0481321775 -5.2252583582 +6177 50.0500016689 -5.220040746 +6178 50.0521729635 -5.2151128397 +6179 50.0546275756 -5.2105166346 +6180 50.0573446048 -5.2062913196 +6181 50.0603009122 -5.2024729432 +6182 50.0634713172 -5.1990941066 +6183 50.06682881 -5.1961836839 +6184 50.0703447816 -5.193766575 +6185 50.073989266 -5.1918634905 +6186 50.0777311953 -5.1904907716 +6187 50.0815386634 -5.1896602479 +6188 50.0853791979 -5.1893791319 +6189 50.0892200368 -5.1896499532 +6190 50.0930284076 -5.1904705327 +6191 50.0967718071 -5.1918339966 +6192 50.1004182793 -5.1937288306 +6193 50.1039366885 -5.1961389742 +6194 50.1072969857 -5.1990439541 +6195 50.1104704664 -5.202419056 +6196 50.1134300161 -5.2062355326 +6197 50.1161503437 -5.2104608476 +6198 50.1186081982 -5.2150589524 +6199 50.1207825685 -5.2199905936 +6200 50.1226548643 -5.2252136485 +6201 50.124209076 -5.2306834863 +6202 50.1254319124 -5.2363533515 +6203 50.1263129153 -5.2421747651 +6204 50.1268445494 -5.2480979426 +6205 50.1270222675 -5.2540722222 +6206 50.0608 -5.3224722222 +6207 50.0648040278 -5.3102815833 +6208 50.067469965 -5.3124470945 +6209 50.0702295787 -5.314308046 +6210 50.0730684722 -5.3158546667 +6211 50.0688138889 -5.3288083333 +6212 50.0608 -5.3224722222 +6213 50.1138611111 -5.1913138889 +6214 50.11029775 -5.2022176389 +6215 50.1078233936 -5.1995584017 +6216 50.1052319388 -5.1971842309 +6217 50.1025369444 -5.1951074722 +6218 50.10585 -5.1849694444 +6219 50.1138611111 -5.1913138889 +6220 50.1018638889 -5.3329861111 +6221 50.0972953889 -5.3160738056 +6222 50.1001392694 -5.3145814639 +6223 50.1029065511 -5.3127741935 +6224 50.1055828333 -5.3106613611 +6225 50.1101472222 -5.3275583333 +6226 50.1018638889 -5.3329861111 +6227 50.0688777778 -5.1752277778 +6228 50.0734629167 -5.19210275 +6229 50.0706204565 -5.1936019857 +6230 50.0678548986 -5.1954154024 +6231 50.0651806111 -5.1975335278 +6232 50.0605916667 -5.1806444444 +6233 50.0688777778 -5.1752277778 +6234 50.1348166667 -5.2606666667 +6235 50.1268269722 -5.26033425 +6236 50.1270095639 -5.2556702386 +6237 50.1269752666 -5.2509978848 +6238 50.12672425 -5.2463415833 +6239 50.1350555556 -5.2466861111 +6240 50.1348166667 -5.2606666667 +6241 50.0357222222 -5.2425861111 +6242 50.0443929444 -5.2429433056 +6243 50.0439831503 -5.2475654006 +6244 50.0437889397 -5.2522213076 +6245 50.0438113333 -5.2568868333 +6246 50.0354833333 -5.2565416667 +6247 50.0357222222 -5.2425861111 +6248 50.0353338744 -5.2317694444 +6249 50.0351572562 -5.2370853375 +6250 50.0346292776 -5.2423447648 +6251 50.0337555467 -5.2474918642 +6252 50.0325453435 -5.2524719738 +6253 50.0310115211 -5.2572322156 +6254 50.0291703683 -5.2617220602 +6255 50.0270414353 -5.2658938646 +6256 50.0246473257 -5.2697033803 +6257 50.0220134548 -5.2731102226 +6258 50.0191677788 -5.2760782991 +6259 50.0161404971 -5.2785761915 +6260 50.0129637305 -5.2805774868 +6261 50.0096711794 -5.2820610542 +6262 50.0062977655 -5.2830112659 +6263 50.0028792609 -5.2834181582 +6264 49.9994519082 -5.283277533 +6265 49.9960520364 -5.2825909971 +6266 49.9927156753 -5.2813659402 +6267 49.9894781746 -5.2796154522 +6268 49.9863738295 -5.2773581795 +6269 49.9834355182 -5.2746181242 +6270 49.9806943547 -5.2714243858 +6271 49.9781793605 -5.2678108511 +6272 49.9759171581 -5.2638158332 +6273 49.9739316906 -5.2594816653 +6274 49.9722439694 -5.2548542522 +6275 49.9708718529 -5.2499825859 +6276 49.9698298588 -5.2449182283 +6277 49.9691290109 -5.2397147684 +6278 49.9687767236 -5.2344272576 +6279 49.9687767236 -5.2291116313 +6280 49.9691290109 -5.2238241205 +6281 49.9698298588 -5.2186206606 +6282 49.9708718529 -5.213556303 +6283 49.9722439694 -5.2086846367 +6284 49.9739316906 -5.2040572236 +6285 49.9759171581 -5.1997230557 +6286 49.9781793605 -5.1957280378 +6287 49.9806943547 -5.1921145031 +6288 49.9834355182 -5.1889207647 +6289 49.9863738295 -5.1861807094 +6290 49.9894781746 -5.1839234367 +6291 49.9927156753 -5.1821729487 +6292 49.9960520364 -5.1809478918 +6293 49.9994519082 -5.1802613559 +6294 50.0028792609 -5.1801207307 +6295 50.0062977655 -5.180527623 +6296 50.0096711794 -5.1814778347 +6297 50.0129637305 -5.1829614021 +6298 50.0161404971 -5.1849626974 +6299 50.0191677788 -5.1874605898 +6300 50.0220134548 -5.1904286663 +6301 50.0246473257 -5.1938355086 +6302 50.0270414353 -5.1976450242 +6303 50.0291703683 -5.2018168287 +6304 50.0310115211 -5.2063066733 +6305 50.0325453435 -5.2110669151 +6306 50.0337555467 -5.2160470246 +6307 50.0346292776 -5.221194124 +6308 50.0351572562 -5.2264535514 +6309 50.0353338744 -5.2317694444 +6310 49.9617730833 -5.2835419444 +6311 49.9753855556 -5.2627449167 +6312 49.9772937977 -5.2663444516 +6313 49.979403434 -5.2696628728 +6314 49.9816973056 -5.2726731667 +6315 49.9680870278 -5.2934640556 +6316 49.9617730833 -5.2835419444 +6317 50.0422724167 -5.1799270833 +6318 50.0286782778 -5.2007712222 +6319 50.0267686512 -5.1971696359 +6320 50.024657554 -5.1938502156 +6321 50.0223621944 -5.19084 +6322 50.0359585278 -5.1699896944 +6323 50.0422724167 -5.1799270833 +6324 49.9944973611 -5.3117936944 +6325 49.9945571944 -5.2821116389 +6326 49.9975243578 -5.2829561989 +6327 50.0005286115 -5.2833808119 +6328 50.0035453056 -5.2833819167 +6329 50.0034878056 -5.3118256944 +6330 49.9944973611 -5.3117936944 +6331 50.00371625 -5.1573170556 +6332 50.0036954167 -5.180168 +6333 50.0006787566 -5.1801480057 +6334 49.9976733054 -5.1805515819 +6335 49.9947037222 -5.1813753611 +6336 49.9947258056 -5.1572850556 +6337 50.00371625 -5.1573170556 +6338 50.0253619444 -5.2954350278 +6339 50.0167982778 -5.2780854722 +6340 50.0194338016 -5.2758280709 +6341 50.0219271581 -5.2732102702 +6342 50.0242579444 -5.2702534167 +6343 50.0324947222 -5.2869394444 +6344 50.0253619444 -5.2954350278 +6345 49.9738475 -5.1683617778 +6346 49.9838324444 -5.1885124444 +6347 49.9813889971 -5.1912391424 +6348 49.9791142377 -5.1942966282 +6349 49.9770267222 -5.1976598889 +6350 49.9667146667 -5.1768470278 +6351 49.9738475 -5.1683617778 +6352 50.0520801944 -5.2389025278 +6353 50.0350520833 -5.2384789167 +6354 50.035307421 -5.2338293861 +6355 50.0352915093 -5.2291630406 +6356 50.0350044722 -5.2245179722 +6357 50.0522232222 -5.2249413611 +6358 50.0520801944 -5.2389025278 +6359 49.9518661389 -5.2224781111 +6360 49.9692269444 -5.2229034722 +6361 49.9688452124 -5.2275257288 +6362 49.9687336718 -5.2321824878 +6363 49.9688932222 -5.2368358889 +6364 49.9517231111 -5.23641025 +6365 49.9518661389 -5.2224781111 +6366 50.4823974866 -4.995375 +6367 50.4822197775 -5.0013939644 +6368 50.4816881703 -5.0073614427 +6369 50.4808072122 -5.0132263927 +6370 50.4795844382 -5.0189386559 +6371 50.4780303064 -5.0244493897 +6372 50.4761581077 -5.0297114877 +6373 50.4739838514 -5.0346799846 +6374 50.4715261273 -5.0393124424 +6375 50.4688059458 -5.0435693141 +6376 50.4658465572 -5.0474142818 +6377 50.462673252 -5.0508145666 +6378 50.4593131434 -5.0537412075 +6379 50.4557949349 -5.0561693067 +6380 50.4521486742 -5.0580782394 +6381 50.4484054954 -5.0594518272 +6382 50.4445973531 -5.0602784716 +6383 50.4407567484 -5.0605512498 +6384 50.4369164519 -5.0602679685 +6385 50.4331092237 -5.0594311786 +6386 50.4293675339 -5.0580481486 +6387 50.4257232862 -5.0561307983 +6388 50.4222075464 -5.0536955929 +6389 50.4188502779 -5.0507633991 +6390 50.4156800876 -5.0473593039 +6391 50.4127239826 -5.043512398 +6392 50.4100071416 -5.0392555263 +6393 50.4075527011 -5.0346250067 +6394 50.4053815597 -5.0296603202 +6395 50.4035122011 -5.024403775 +6396 50.401960538 -5.0189001474 +6397 50.4007397771 -5.0131963018 +6398 50.3998603079 -5.0073407941 +6399 50.3993296149 -5.0013834612 +6400 50.399152214 -4.995375 +6401 50.3993296149 -4.9893665388 +6402 50.3998603079 -4.9834092059 +6403 50.4007397771 -4.9775536982 +6404 50.401960538 -4.9718498526 +6405 50.4035122011 -4.966346225 +6406 50.4053815597 -4.9610896798 +6407 50.4075527011 -4.9561249933 +6408 50.4100071416 -4.9514944737 +6409 50.4127239826 -4.947237602 +6410 50.4156800876 -4.9433906961 +6411 50.4188502779 -4.9399866009 +6412 50.4222075464 -4.9370544071 +6413 50.4257232862 -4.9346192017 +6414 50.4293675339 -4.9327018514 +6415 50.4331092237 -4.9313188214 +6416 50.4369164519 -4.9304820315 +6417 50.4407567484 -4.9301987502 +6418 50.4445973531 -4.9304715284 +6419 50.4484054954 -4.9312981728 +6420 50.4521486742 -4.9326717606 +6421 50.4557949349 -4.9345806933 +6422 50.4593131434 -4.9370087925 +6423 50.462673252 -4.9399354334 +6424 50.4658465572 -4.9433357182 +6425 50.4688059458 -4.9471806859 +6426 50.4715261273 -4.9514375576 +6427 50.4739838514 -4.9560700154 +6428 50.4761581077 -4.9610385123 +6429 50.4780303064 -4.9663006103 +6430 50.4795844382 -4.9718113441 +6431 50.4808072122 -4.9775236073 +6432 50.4816881703 -4.9833885573 +6433 50.4822197775 -4.9893560356 +6434 50.4823974866 -4.995375 +6435 50.4659722222 -5.0762666667 +6436 50.4579050556 -5.0547863333 +6437 50.4605952669 -5.0526992207 +6438 50.4631823971 -5.0503135172 +6439 50.4656529722 -5.0476416111 +6440 50.4737166667 -5.0691111111 +6441 50.4659722222 -5.0762666667 +6442 50.4169 -4.9182166667 +6443 50.4236155278 -4.9360059167 +6444 50.4209275579 -4.9380977536 +6445 50.4183428509 -4.9404871378 +6446 50.4158748333 -4.9431616111 +6447 50.4091555556 -4.9253611111 +6448 50.4169 -4.9182166667 +6449 50.7759120447 -3.4138111111 +6450 50.775734343 -3.4198676675 +6451 50.7752027579 -3.4258724149 +6452 50.7743218365 -3.4317739908 +6453 50.7730991138 -3.4375219223 +6454 50.7715450477 -3.4430670607 +6455 50.7696729288 -3.4483620045 +6456 50.7674987661 -3.4533615069 +6457 50.7650411491 -3.4580228647 +6458 50.7623210878 -3.4623062837 +6459 50.7593618318 -3.4661752198 +6460 50.7561886708 -3.4695966899 +6461 50.7528287174 -3.4725415531 +6462 50.7493106742 -3.4749847572 +6463 50.7456645876 -3.4769055504 +6464 50.7419215906 -3.4782876544 +6465 50.7381136364 -3.4791194006 +6466 50.7342732247 -3.4793938246 +6467 50.7304331244 -3.4791087213 +6468 50.726626094 -3.4782666594 +6469 50.7228846017 -3.4768749545 +6470 50.7192405493 -3.4749456026 +6471 50.7157250007 -3.4724951729 +6472 50.7123679174 -3.4695446637 +6473 50.7091979042 -3.4661193192 +6474 50.7062419664 -3.4622484124 +6475 50.7035252806 -3.4579649933 +6476 50.7010709818 -3.4533056062 +6477 50.6988999669 -3.4483099782 +6478 50.6970307181 -3.4430206805 +6479 50.6954791466 -3.4374827676 +6480 50.6942584582 -3.4317433949 +6481 50.6933790415 -3.4258514198 +6482 50.6928483801 -3.4198569881 +6483 50.6926709899 -3.4138111111 +6484 50.6928483801 -3.4077652341 +6485 50.6933790415 -3.4017708025 +6486 50.6942584582 -3.3958788273 +6487 50.6954791466 -3.3901394546 +6488 50.6970307181 -3.3846015417 +6489 50.6988999669 -3.379312244 +6490 50.7010709818 -3.374316616 +6491 50.7035252806 -3.3696572289 +6492 50.7062419664 -3.3653738098 +6493 50.7091979042 -3.361502903 +6494 50.7123679174 -3.3580775585 +6495 50.7157250007 -3.3551270493 +6496 50.7192405493 -3.3526766197 +6497 50.7228846017 -3.3507472677 +6498 50.726626094 -3.3493555629 +6499 50.7304331244 -3.348513501 +6500 50.7342732247 -3.3482283977 +6501 50.7381136364 -3.3485028216 +6502 50.7419215906 -3.3493345678 +6503 50.7456645876 -3.3507166719 +6504 50.7493106742 -3.352637465 +6505 50.7528287174 -3.3550806691 +6506 50.7561886708 -3.3580255323 +6507 50.7593618318 -3.3614470024 +6508 50.7623210878 -3.3653159385 +6509 50.7650411491 -3.3695993576 +6510 50.7674987661 -3.3742607153 +6511 50.7696729288 -3.3792602178 +6512 50.7715450477 -3.3845551615 +6513 50.7730991138 -3.3901002999 +6514 50.7743218365 -3.3958482314 +6515 50.7752027579 -3.4017498073 +6516 50.775734343 -3.4077545547 +6517 50.7759120447 -3.4138111111 +6518 50.7169166667 -3.4950583333 +6519 50.7200062778 -3.4754004444 +6520 50.7228603054 -3.4768640098 +6521 50.7257738522 -3.4779999174 +6522 50.7287317778 -3.4788021944 +6523 50.7256444444 -3.4984444444 +6524 50.7169166667 -3.4950583333 +6525 50.7515472222 -3.3329055556 +6526 50.7485441667 -3.3521841667 +6527 50.7456883341 -3.3507272916 +6528 50.7427732951 -3.3495987816 +6529 50.7398142222 -3.3488044444 +6530 50.7428194444 -3.3295111111 +6531 50.7515472222 -3.3329055556 +6532 50.8932956049 -3.2347222222 +6533 50.8931190092 -3.2401351738 +6534 50.8925910977 -3.2454906252 +6535 50.8917174782 -3.2507316905 +6536 50.8905074303 -3.2558027069 +6537 50.888973806 -3.2606498284 +6538 50.8871328929 -3.2652216011 +6539 50.8850042399 -3.2694695114 +6540 50.8826104486 -3.2733485023 +6541 50.8799769321 -3.2768174528 +6542 50.877131644 -3.279839613 +6543 50.8741047808 -3.2823829938 +6544 50.8709284596 -3.2844207029 +6545 50.8676363769 -3.2859312278 +6546 50.8642634502 -3.2868986599 +6547 50.8608454468 -3.2873128583 +6548 50.8574186042 -3.2871695533 +6549 50.8540192458 -3.2864703856 +6550 50.8506833957 -3.2852228848 +6551 50.8474463977 -3.2834403834 +6552 50.8443425409 -3.2811418721 +6553 50.8414046975 -3.2783517935 +6554 50.8386639756 -3.2750997803 +6555 50.8361493907 -3.2714203384 +6556 50.8338875599 -3.2673524801 +6557 50.8319024213 -3.2629393099 +6558 50.8302149816 -3.2582275683 +6559 50.8288430954 -3.253267138 +6560 50.827801277 -3.2481105182 +6561 50.8271005476 -3.2428122708 +6562 50.82674832 -3.237428447 +6563 50.82674832 -3.2320159975 +6564 50.8271005476 -3.2266321737 +6565 50.827801277 -3.2213339263 +6566 50.8288430954 -3.2161773064 +6567 50.8302149816 -3.2112168762 +6568 50.8319024213 -3.2065051345 +6569 50.8338875599 -3.2020919643 +6570 50.8361493907 -3.198024106 +6571 50.8386639756 -3.1943446642 +6572 50.8414046975 -3.1910926509 +6573 50.8443425409 -3.1883025723 +6574 50.8474463977 -3.186004061 +6575 50.8506833957 -3.1842215597 +6576 50.8540192458 -3.1829740588 +6577 50.8574186042 -3.1822748912 +6578 50.8608454468 -3.1821315861 +6579 50.8642634502 -3.1825457846 +6580 50.8676363769 -3.1835132166 +6581 50.8709284596 -3.1850237416 +6582 50.8741047808 -3.1870614507 +6583 50.877131644 -3.1896048314 +6584 50.8799769321 -3.1926269917 +6585 50.8826104486 -3.1960959421 +6586 50.8850042399 -3.1999749331 +6587 50.8871328929 -3.2042228433 +6588 50.888973806 -3.208794616 +6589 50.8905074303 -3.2136417376 +6590 50.8917174782 -3.2187127539 +6591 50.8925910977 -3.2239538193 +6592 50.8931190092 -3.2293092706 +6593 50.8932956049 -3.2347222222 +6594 50.8198666667 -3.2805972222 +6595 50.8321895278 -3.2636403056 +6596 50.8339522696 -3.2674813106 +6597 50.8359269644 -3.2710560959 +6598 50.8380975556 -3.2743355833 +6599 50.825775 -3.2912888889 +6600 50.8198666667 -3.2805972222 +6601 50.9000361111 -3.1889333333 +6602 50.8878178611 -3.2058049722 +6603 50.886054867 -3.2019593037 +6604 50.8840796765 -3.1983808085 +6605 50.8819083889 -3.1950986389 +6606 50.8941277778 -3.1782222222 +6607 50.9000361111 -3.1889333333 +6608 51.0047548483 -2.9388138889 +6609 51.0045771522 -2.9449001943 +6610 51.0040455843 -2.950934435 +6611 51.0031646914 -2.9568649954 +6612 51.0019420085 -2.9626411535 +6613 51.0003879933 -2.9682135183 +6614 50.9985159364 -2.9735344549 +6615 50.9963418465 -2.9785584938 +6616 50.9938843127 -2.9832427217 +6617 50.9911643446 -2.9875471493 +6618 50.9882051916 -2.9914350528 +6619 50.9850321428 -2.9948732879 +6620 50.9816723101 -2.9978325712 +6621 50.9781543952 -3.0002877285 +6622 50.974508444 -3.0022179071 +6623 50.9707655884 -3.0036067504 +6624 50.9669577805 -3.0044425336 +6625 50.963117519 -3.0047182595 +6626 50.9592775715 -3.004431714 +6627 50.955470695 -3.0035854798 +6628 50.9517293565 -3.0021869098 +6629 50.9480854563 -3.00024806 +6630 50.9445700566 -2.9977855824 +6631 50.9412131175 -2.9948205789 +6632 50.9380432423 -2.9913784186 +6633 50.9350874347 -2.9874885185 +6634 50.93237087 -2.983184091 +6635 50.9299166817 -2.9785018596 +6636 50.9277457654 -2.9734817459 +6637 50.9258766021 -2.9681665295 +6638 50.9243251021 -2.9626014849 +6639 50.9231044702 -2.956833998 +6640 50.9222250943 -2.9509131644 +6641 50.9216944577 -2.9448893748 +6642 50.9215170757 -2.9388138889 +6643 50.9216944577 -2.932738403 +6644 50.9222250943 -2.9267146134 +6645 50.9231044702 -2.9207937798 +6646 50.9243251021 -2.9150262928 +6647 50.9258766021 -2.9094612483 +6648 50.9277457654 -2.9041460319 +6649 50.9299166817 -2.8991259182 +6650 50.93237087 -2.8944436868 +6651 50.9350874347 -2.8901392593 +6652 50.9380432423 -2.8862493592 +6653 50.9412131175 -2.8828071989 +6654 50.9445700566 -2.8798421954 +6655 50.9480854563 -2.8773797178 +6656 50.9517293565 -2.875440868 +6657 50.955470695 -2.874042298 +6658 50.9592775715 -2.8731960637 +6659 50.963117519 -2.8729095182 +6660 50.9669577805 -2.8731852442 +6661 50.9707655884 -2.8740210274 +6662 50.974508444 -2.8754098707 +6663 50.9781543952 -2.8773400493 +6664 50.9816723101 -2.8797952066 +6665 50.9850321428 -2.8827544899 +6666 50.9882051916 -2.886192725 +6667 50.9911643446 -2.8900806285 +6668 50.9938843127 -2.894385056 +6669 50.9963418465 -2.899069284 +6670 50.9985159364 -2.9040933229 +6671 51.0003879933 -2.9094142595 +6672 51.0019420085 -2.9149866243 +6673 51.0031646914 -2.9207627824 +6674 51.0040455843 -2.9266933427 +6675 51.0045771522 -2.9327275835 +6676 51.0047548483 -2.9388138889 +6677 50.9183033056 -2.9648844444 +6678 50.9239230833 -2.9608878056 +6679 50.9250301094 -2.9653039687 +6680 50.9263353435 -2.9695825808 +6681 50.927832 -2.9737014167 +6682 50.9219914444 -2.9778534167 +6683 50.9183033056 -2.9648844444 +6684 51.0141108611 -2.91223225 +6685 51.0030484167 -2.92012775 +6686 51.0020936564 -2.9156159388 +6687 51.00093597 -2.9112251741 +6688 50.9995813889 -2.9069783611 +6689 51.0104227778 -2.8992376111 +6690 51.0141108611 -2.91223225 +6691 50.9538749444 -3.0216006389 +6692 50.9549248056 -3.0034171389 +6693 50.9578865645 -3.0041882275 +6694 50.9608757179 -3.0046194034 +6695 50.9638767222 -3.0047083611 +6696 50.9628273889 -3.0228821389 +6697 50.9538749444 -3.0216006389 +6698 50.9723541944 -2.8560128611 +6699 50.971328 -2.8741930833 +6700 50.9683656014 -2.8734281588 +6701 50.9653760928 -2.8730034372 +6702 50.9623750278 -2.8729210556 +6703 50.96340175 -2.8547311111 +6704 50.9723541944 -2.8560128611 +6705 51.0101076389 -2.9685856389 +6706 51.0015711389 -2.9641047222 +6707 51.0026227467 -2.9596462924 +6708 51.0034685703 -2.9550791053 +6709 51.0041041944 -2.950427 +6710 51.01293025 -2.9550573333 +6711 51.0101076389 -2.9685856389 +6712 50.9188734444 -2.9058088333 +6713 50.9258746667 -2.9094674444 +6714 50.9246351369 -2.913795743 +6715 50.9235959522 -2.9182540045 +6716 50.9227625 -2.9228190556 +6717 50.9160507778 -2.9193098333 +6718 50.9188734444 -2.9058088333 +6719 50.9714693611 -2.6762913333 +6720 50.9701675861 -2.6813214099 +6721 50.9685455593 -2.6861121821 +6722 50.9666205383 -2.6906126594 +6723 50.9644130177 -2.6947749661 +6724 50.9619464963 -2.6985548452 +6725 50.9592472264 -2.7019121291 +6726 50.9563439325 -2.7048111668 +6727 50.9532675051 -2.7072212013 +6728 50.9500506702 -2.7091166941 +6729 50.9467276407 -2.7104775937 +6730 50.9433337517 -2.7112895447 +6731 50.9399050838 -2.7115440354 +6732 50.9364780797 -2.7112384838 +6733 50.9330891564 -2.7103762595 +6734 50.9297743184 -2.7089666428 +6735 50.9265687754 -2.7070247211 +6736 50.9235065695 -2.7045712243 +6737 50.9206202139 -2.7016323001 +6738 50.917940349 -2.6982392335 +6739 50.915495418 -2.694428112 +6740 50.9133113666 -2.690239441 +6741 50.9114113683 -2.685717713 +6742 50.9098155805 -2.6809109363 +6743 50.908540931 -2.6758701262 +6744 50.9076009399 -2.6706487661 +6745 50.9070055769 -2.6653022429 +6746 50.9067611562 -2.6598872626 +6747 50.90687027 -2.6544612525 +6748 50.907331761 -2.6490817564 +6749 50.908140735 -2.6438058276 +6750 50.9092886121 -2.6386894283 +6751 50.910763217 -2.6337868387 +6752 50.9125489081 -2.6291500848 +6753 50.9146267417 -2.6248283884 +6754 50.9169746722 -2.6208676465 +6755 50.9195677849 -2.6173099448 +6756 50.922378559 -2.614193111 +6757 50.9253771585 -2.6115503118 +6758 50.928531748 -2.6094096989 +6759 50.9318088292 -2.6077941069 +6760 50.9351735959 -2.6067208071 +6761 50.9385903034 -2.6062013196 +6762 50.9420226471 -2.6062412861 +6763 50.9454341484 -2.6068404051 +6764 50.9487885423 -2.6079924294 +6765 50.9520501632 -2.6096852278 +6766 50.9551843245 -2.6119009088 +6767 50.9581576886 -2.6146160072 +6768 50.9609386219 -2.6178017294 +6769 50.9634975325 -2.6214242569 +6770 50.9658071869 -2.6254451044 +6771 50.967843 -2.6298215278 +6772 50.9714693611 -2.6762913333 +6773 50.9371277778 -2.7375611111 +6774 50.9366077222 -2.7112603056 +6775 50.9396068368 -2.7115396944 +6776 50.9426096531 -2.7113901 +6777 50.9455917222 -2.7108126389 +6778 50.9461111111 -2.7371027778 +6779 50.9371277778 -2.7375611111 +6780 50.9429222222 -2.5801416667 +6781 50.9434709722 -2.6064268056 +6782 50.9404710151 -2.6061537863 +6783 50.9374677222 -2.6063099945 +6784 50.9344855556 -2.6068940556 +6785 50.9339361111 -2.5805972222 +6786 50.9429222222 -2.5801416667 +6787 51.0005172124 -2.1536111111 +6788 51.0003406194 -2.1590365291 +6789 50.9998127162 -2.1644043138 +6790 50.9989391106 -2.1696574483 +6791 50.9977290819 -2.1747401408 +6792 50.9961954822 -2.1795984212 +6793 50.9943545989 -2.1841807168 +6794 50.9922259806 -2.1884384021 +6795 50.9898322288 -2.1923263164 +6796 50.9871987564 -2.1958032439 +6797 50.9843535166 -2.1988323506 +6798 50.9813267053 -2.2013815737 +6799 50.9781504395 -2.2034239597 +6800 50.9748584151 -2.2049379469 +6801 50.9714855491 -2.2059075905 +6802 50.9680676081 -2.2063227271 +6803 50.964640829 -2.2061790777 +6804 50.9612415346 -2.2054782875 +6805 50.9579057482 -2.2042279037 +6806 50.9546688129 -2.2024412905 +6807 50.951565017 -2.2001374823 +6808 50.948627232 -2.1973409787 +6809 50.9458865651 -2.1940814806 +6810 50.9433720314 -2.1903935737 +6811 50.941110247 -2.1863163598 +6812 50.9391251494 -2.1818930427 +6813 50.9374377449 -2.1771704701 +6814 50.9360658874 -2.1721986392 +6815 50.9350240909 -2.1670301693 +6816 50.9343233764 -2.1617197477 +6817 50.9339711562 -2.1563235537 +6818 50.9339711562 -2.1508986685 +6819 50.9343233764 -2.1455024745 +6820 50.9350240909 -2.1401920529 +6821 50.9360658874 -2.135023583 +6822 50.9374377449 -2.1300517522 +6823 50.9391251494 -2.1253291795 +6824 50.941110247 -2.1209058624 +6825 50.9433720314 -2.1168286486 +6826 50.9458865651 -2.1131407416 +6827 50.948627232 -2.1098812435 +6828 50.951565017 -2.1070847399 +6829 50.9546688129 -2.1047809318 +6830 50.9579057482 -2.1029943185 +6831 50.9612415346 -2.1017439347 +6832 50.964640829 -2.1010431445 +6833 50.9680676081 -2.1008994951 +6834 50.9714855491 -2.1013146317 +6835 50.9748584151 -2.1022842754 +6836 50.9781504395 -2.1037982626 +6837 50.9813267053 -2.1058406485 +6838 50.9843535166 -2.1083898716 +6839 50.9871987564 -2.1114189783 +6840 50.9898322288 -2.1148959058 +6841 50.9922259806 -2.1187838201 +6842 50.9943545989 -2.1230415054 +6843 50.9961954822 -2.127623801 +6844 50.9977290819 -2.1324820814 +6845 50.9989391106 -2.137564774 +6846 50.9998127162 -2.1428179084 +6847 51.0003406194 -2.1481856932 +6848 51.0005172124 -2.1536111111 +6849 50.9520972222 -2.2270083333 +6850 50.9555675556 -2.2029971944 +6851 50.9584260794 -2.2044610998 +6852 50.9613562969 -2.2055112153 +6853 50.9643343611 -2.2061389167 +6854 50.9608611111 -2.2301694444 +6855 50.9520972222 -2.2270083333 +6856 50.9824361111 -2.0802805556 +6857 50.9789954444 -2.1042831944 +6858 50.9761396879 -2.1028044889 +6859 50.9732113938 -2.1017397236 +6860 50.9702344167 -2.1010975 +6861 50.9736722222 -2.0771138889 +6862 50.9824361111 -2.0802805556 +6863 50.8216839385 -1.8425138889 +6864 50.8215062379 -1.8485763644 +6865 50.8209746562 -1.8545869801 +6866 50.8200937406 -1.860494323 +6867 50.8188710258 -1.8662478708 +6868 50.8173169699 -1.8717984264 +6869 50.8154448635 -1.8770985419 +6870 50.8132707154 -1.8821029264 +6871 50.810813115 -1.8867688346 +6872 50.8080930724 -1.8910564338 +6873 50.805133837 -1.8949291438 +6874 50.8019606985 -1.8983539496 +6875 50.7986007693 -1.901301682 +6876 50.7950827518 -1.9037472645 +6877 50.7914366922 -1.9056699251 +6878 50.7876937236 -1.9070533701 +6879 50.7838857986 -1.9078859195 +6880 50.780045417 -1.9081606025 +6881 50.7762053473 -1.9078752123 +6882 50.7723983477 -1.9070323202 +6883 50.7686568861 -1.9056392495 +6884 50.7650128642 -1.9037080077 +6885 50.7614973454 -1.9012551809 +6886 50.758140291 -1.8983017878 +6887 50.7549703053 -1.8948730975 +6888 50.7520143936 -1.8909984115 +6889 50.7492977321 -1.8867108124 +6890 50.7468434554 -1.88204688 +6891 50.7446724602 -1.87704638 +6892 50.7428032284 -1.8717519253 +6893 50.7412516713 -1.866208614 +6894 50.7400309942 -1.8604636474 +6895 50.7391515856 -1.8545659302 +6896 50.7386209292 -1.8485656572 +6897 50.7384435406 -1.8425138889 +6898 50.7386209292 -1.8364621206 +6899 50.7391515856 -1.8304618475 +6900 50.7400309942 -1.8245641304 +6901 50.7412516713 -1.8188191638 +6902 50.7428032284 -1.8132758525 +6903 50.7446724602 -1.8079813978 +6904 50.7468434554 -1.8029808978 +6905 50.7492977321 -1.7983169654 +6906 50.7520143936 -1.7940293662 +6907 50.7549703053 -1.7901546803 +6908 50.758140291 -1.78672599 +6909 50.7614973454 -1.7837725969 +6910 50.7650128642 -1.78131977 +6911 50.7686568861 -1.7793885283 +6912 50.7723983477 -1.7779954575 +6913 50.7762053473 -1.7771525655 +6914 50.780045417 -1.7768671752 +6915 50.7838857986 -1.7771418583 +6916 50.7876937236 -1.7779744077 +6917 50.7914366922 -1.7793578527 +6918 50.7950827518 -1.7812805133 +6919 50.7986007693 -1.7837260958 +6920 50.8019606985 -1.7866738282 +6921 50.805133837 -1.790098634 +6922 50.8080930724 -1.793971344 +6923 50.810813115 -1.7982589432 +6924 50.8132707154 -1.8029248514 +6925 50.8154448635 -1.8079292359 +6926 50.8173169699 -1.8132293514 +6927 50.8188710258 -1.818779907 +6928 50.8200937406 -1.8245334547 +6929 50.8209746562 -1.8304407977 +6930 50.8215062379 -1.8364514133 +6931 50.8216839385 -1.8425138889 +6932 50.7626972222 -1.9189138889 +6933 50.7652141944 -1.9038303611 +6934 50.768054234 -1.9053602225 +6935 50.7709567886 -1.906563561 +6936 50.7739067778 -1.9074340556 +6937 50.7713916667 -1.9225055556 +6938 50.7626972222 -1.9189138889 +6939 50.798375 -1.7601111111 +6940 50.7948912778 -1.7811646111 +6941 50.7920496202 -1.7796401409 +6942 50.7891457046 -1.7784428843 +6943 50.7861946389 -1.7775790278 +6944 50.7896805556 -1.7565111111 +6945 50.798375 -1.7601111111 +6946 50.9835728651 -1.3566666667 +6947 50.9833962716 -1.3620901095 +6948 50.9828683672 -1.3674559401 +6949 50.9819947593 -1.3727071623 +6950 50.9807847276 -1.3777880049 +6951 50.979251124 -1.3826445173 +6952 50.977410236 -1.3872251457 +6953 50.9752816122 -1.3914812822 +6954 50.9728878542 -1.3953677827 +6955 50.9702543748 -1.3988434463 +6956 50.9674091274 -1.4018714524 +6957 50.9643823079 -1.4044197499 +6958 50.9612060334 -1.4064613948 +6959 50.9579139998 -1.4079748335 +6960 50.9545411242 -1.4089441267 +6961 50.9511231733 -1.4093591147 +6962 50.9476963842 -1.4092155198 +6963 50.9442970796 -1.4085149867 +6964 50.9409612832 -1.4072650597 +6965 50.937724338 -1.4054790979 +6966 50.9346205324 -1.403176129 +6967 50.9316827382 -1.4003806434 +6968 50.9289420627 -1.3971223312 +6969 50.9264275208 -1.3934357654 +6970 50.9241657291 -1.3893600339 +6971 50.9221806251 -1.3849383244 +6972 50.920493215 -1.3802174678 +6973 50.919121353 -1.3752474433 +6974 50.918079553 -1.3700808509 +6975 50.9173788361 -1.3647723582 +6976 50.9170266148 -1.3593781241 +6977 50.9170266148 -1.3539552092 +6978 50.9173788361 -1.3485609751 +6979 50.918079553 -1.3432524824 +6980 50.919121353 -1.3380858901 +6981 50.920493215 -1.3331158655 +6982 50.9221806251 -1.3283950089 +6983 50.9241657291 -1.3239732994 +6984 50.9264275208 -1.3198975679 +6985 50.9289420627 -1.3162110021 +6986 50.9316827382 -1.31295269 +6987 50.9346205324 -1.3101572043 +6988 50.937724338 -1.3078542354 +6989 50.9409612832 -1.3060682736 +6990 50.9442970796 -1.3048183467 +6991 50.9476963842 -1.3041178135 +6992 50.9511231733 -1.3039742186 +6993 50.9545411242 -1.3043892067 +6994 50.9579139998 -1.3053584999 +6995 50.9612060334 -1.3068719385 +6996 50.9643823079 -1.3089135835 +6997 50.9674091274 -1.3114618809 +6998 50.9702543748 -1.314489887 +6999 50.9728878542 -1.3179655506 +7000 50.9752816122 -1.3218520511 +7001 50.977410236 -1.3261081877 +7002 50.979251124 -1.330688816 +7003 50.9807847276 -1.3355453284 +7004 50.9819947593 -1.340626171 +7005 50.9828683672 -1.3458773932 +7006 50.9833962716 -1.3512432239 +7007 50.9835728651 -1.3566666667 +7008 50.8996805556 -1.3774111111 +7009 50.9176806667 -1.3674003333 +7010 50.9184244585 -1.3720051772 +7011 50.9194274358 -1.3764853887 +7012 50.9206814444 -1.3808045556 +7013 50.9026638889 -1.3908194444 +7014 50.8996805556 -1.3774111111 +7015 51.0010722222 -1.3360194444 +7016 50.9829045278 -1.3461549722 +7017 50.982173002 -1.3415383674 +7018 50.9811815632 -1.3370452143 +7019 50.9799383056 -1.3327121667 +7020 50.9980888889 -1.3225805556 +7021 51.0010722222 -1.3360194444 +7022 50.8028401667 -1.1582839167 +7023 50.8047583725 -1.1571086989 +7024 50.8066666667 -1.1558333333 +7025 50.8469444444 -1.1880555556 +7026 50.8479990642 -1.1932506097 +7027 50.8487067777 -1.1985905574 +7028 50.8490599417 -1.2040177313 +7029 50.8490547418 -1.2094735156 +7030 50.8486912341 -1.2148989838 +7031 50.8479733448 -1.220235539 +7032 50.846908827 -1.2254255503 +7033 50.845509177 -1.2304129795 +7034 50.8437895092 -1.235143989 +7035 50.8417683916 -1.2395675256 +7036 50.8394676448 -1.2436358739 +7037 50.8369121049 -1.2473051718 +7038 50.8341293541 -1.250535884 +7039 50.831149422 -1.2532932278 +7040 50.82800446 -1.2555475458 +7041 50.8247283936 -1.2572746236 +7042 50.8213565552 -1.2584559467 +7043 50.8179253026 -1.259078896 +7044 50.8144716262 -1.2591368788 +7045 50.8110327501 -1.2586293949 +7046 50.8076457307 -1.2575620362 +7047 50.8043470578 -1.2559464215 +7048 50.8011722618 -1.2538000663 +7049 50.7981555319 -1.2511461895 +7050 50.7953293487 -1.2480134597 +7051 50.7927241356 -1.244435683 +7052 50.7903679324 -1.2404514373 +7053 50.788286095 -1.2361036556 +7054 50.7865010235 -1.2314391635 +7055 50.7850319225 -1.2265081763 +7056 50.7838945957 -1.2213637601 +7057 50.7831012768 -1.2160612632 +7058 50.7826604986 -1.210657724 +7059 50.7825770017 -1.2052112607 +7060 50.7828516843 -1.1997804503 +7061 50.783481592 -1.1944237025 +7062 50.7844599498 -1.1891986355 +7063 50.7857762344 -1.1841614599 +7064 50.7874162864 -1.1793663774 +7065 50.7893624625 -1.1748650004 +7066 50.7915938234 -1.1707057986 +7067 50.7940863583 -1.1669335786 +7068 50.7968132421 -1.1635890021 +7069 50.7997451229 -1.1607081469 +7070 50.8028401667 -1.1582839167 +7071 50.7780111111 -1.2564055556 +7072 50.7892997778 -1.2384847222 +7073 50.7912314979 -1.2421148936 +7074 50.793362658 -1.2454559012 +7075 50.7956759444 -1.2484805278 +7076 50.7843916667 -1.2663916667 +7077 50.7780111111 -1.2564055556 +7078 50.8542138889 -1.1553555556 +7079 50.83812125 -1.1809916111 +7080 50.82969575 -1.1742489167 +7081 50.8478333333 -1.1453527778 +7082 50.8542138889 -1.1553555556 +7083 50.8027966111 -1.1581221111 +7084 50.8036983648 -1.1529473377 +7085 50.8049300154 -1.1479446644 +7086 50.8064787134 -1.1431662976 +7087 50.8083283002 -1.1386621169 +7088 50.8104594759 -1.1344791567 +7089 50.8128499992 -1.1306611169 +7090 50.8154749189 -1.1272479066 +7091 50.818306833 -1.1242752277 +7092 50.8213161733 -1.1217742 +7093 50.8244715133 -1.1197710347 +7094 50.8277398956 -1.118286757 +7095 50.831087175 -1.1173369832 +7096 50.8344783747 -1.1169317532 +7097 50.8378780514 -1.1170754206 +7098 50.8412506657 -1.1177666027 +7099 50.8445609533 -1.1189981896 +7100 50.8477742946 -1.120757414 +7101 50.8508570765 -1.12302598 +7102 50.8537770454 -1.1257802508 +7103 50.8565036455 -1.1289914919 +7104 50.859008339 -1.1326261697 +7105 50.8612649066 -1.1366463005 +7106 50.8632497227 -1.1410098467 +7107 50.8649420041 -1.1456711573 +7108 50.8663240286 -1.1505814465 +7109 50.867381322 -1.1556893061 +7110 50.8681028098 -1.1609412463 +7111 50.8684809347 -1.1662822588 +7112 50.8685117359 -1.1716563965 +7113 50.8681948906 -1.177007363 +7114 50.8675337178 -1.1822791063 +7115 50.8665351432 -1.1874164094 +7116 50.8652096263 -1.1923654723 +7117 50.8635710497 -1.1970744782 +7118 50.8616365735 -1.201494139 +7119 50.8594264543 -1.2055782131 +7120 50.8569638318 -1.2092839904 +7121 50.8542744858 -1.2125727394 +7122 50.8513865649 -1.2154101121 +7123 50.8483333333 -1.2177777778 +7124 50.8488638569 -1.212811389 +7125 50.8490916235 -1.2077876194 +7126 50.8490145484 -1.2027524466 +7127 50.8486333371 -1.1977519533 +7128 50.8479514785 -1.1928319027 +7129 50.8469444444 -1.1880555556 +7130 50.8066666667 -1.1558333333 +7131 50.8046934234 -1.1568187649 +7132 50.8027966111 -1.1581221111 +7133 50.8926428309 -0.7592222222 +7134 50.8924662351 -0.7646350982 +7135 50.8919383236 -0.7699904746 +7136 50.891064704 -0.7752314667 +7137 50.889854656 -0.7803024122 +7138 50.8883210315 -0.7851494661 +7139 50.8864801183 -0.7897211749 +7140 50.884351465 -0.7939690258 +7141 50.8819576735 -0.7978479626 +7142 50.8793241567 -0.8013168646 +7143 50.8764788684 -0.8043389827 +7144 50.8734520048 -0.806882328 +7145 50.8702756833 -0.8089200087 +7146 50.8669836003 -0.8104305127 +7147 50.8636106732 -0.8113979313 +7148 50.8601926694 -0.8118121241 +7149 50.8567658264 -0.8116688211 +7150 50.8533664676 -0.8109696633 +7151 50.8500306172 -0.8097221799 +7152 50.8467936188 -0.8079397036 +7153 50.8436897616 -0.8056412244 +7154 50.8407519178 -0.8028511848 +7155 50.8380111956 -0.799599217 +7156 50.8354966104 -0.7959198265 +7157 50.8332347793 -0.791852025 +7158 50.8312496404 -0.7874389163 +7159 50.8295622006 -0.7827272404 +7160 50.8281903142 -0.7777668794 +7161 50.8271484956 -0.7726103315 +7162 50.8264477661 -0.767312158 +7163 50.8260955385 -0.7619284093 +7164 50.8260955385 -0.7565160352 +7165 50.8264477661 -0.7511322865 +7166 50.8271484956 -0.745834113 +7167 50.8281903142 -0.740677565 +7168 50.8295622006 -0.735717204 +7169 50.8312496404 -0.7310055281 +7170 50.8332347793 -0.7265924195 +7171 50.8354966104 -0.722524618 +7172 50.8380111956 -0.7188452275 +7173 50.8407519178 -0.7155932597 +7174 50.8436897616 -0.7128032201 +7175 50.8467936188 -0.7105047409 +7176 50.8500306172 -0.7087222645 +7177 50.8533664676 -0.7074747811 +7178 50.8567658264 -0.7067756234 +7179 50.8601926694 -0.7066323204 +7180 50.8636106732 -0.7070465132 +7181 50.8669836003 -0.7080139318 +7182 50.8702756833 -0.7095244357 +7183 50.8734520048 -0.7115621164 +7184 50.8764788684 -0.7141054617 +7185 50.8793241567 -0.7171275798 +7186 50.8819576735 -0.7205964818 +7187 50.884351465 -0.7244754186 +7188 50.8864801183 -0.7287232695 +7189 50.8883210315 -0.7332949784 +7190 50.889854656 -0.7381420322 +7191 50.891064704 -0.7432129777 +7192 50.8919383236 -0.7484539698 +7193 50.8924662351 -0.7538093463 +7194 50.8926428309 -0.7592222222 +7195 50.8306472222 -0.8182694444 +7196 50.8382355 -0.7998924444 +7197 50.8406427633 -0.8027345357 +7198 50.8432024379 -0.8052225033 +7199 50.8458936944 -0.8073360278 +7200 50.8381805556 -0.8260138889 +7201 50.8306472222 -0.8182694444 +7202 50.8907361111 -0.6984805556 +7203 50.8817591667 -0.7203087222 +7204 50.8794467216 -0.7172734829 +7205 50.8769704557 -0.7145805628 +7206 50.8743505833 -0.7122518611 +7207 50.8832027778 -0.690725 +7208 50.8907361111 -0.6984805556 +7209 50.8686861111 -0.8341805556 +7210 50.8653005833 -0.8109841389 +7211 50.8682414599 -0.8099217522 +7212 50.871109396 -0.8084429209 +7213 50.8738808333 -0.8065597222 +7214 50.8774444444 -0.830975 +7215 50.8686861111 -0.8341805556 +7216 50.8557472222 -0.6829166667 +7217 50.85923425 -0.7066161944 +7218 50.8562211947 -0.7068499452 +7219 50.8532338934 -0.7075135292 +7220 50.8502968611 -0.7086014167 +7221 50.8469888889 -0.6861194444 +7222 50.8557472222 -0.6829166667 +7223 50.8937666667 -0.8157194444 +7224 50.8813309167 -0.7987409722 +7225 50.883496282 -0.7954479731 +7226 50.8854649223 -0.7918594971 +7227 50.8872207778 -0.7880047778 +7228 50.8996361111 -0.8049527778 +7229 50.8937666667 -0.8157194444 +7230 50.8249722222 -0.7032166667 +7231 50.8372372778 -0.7198981944 +7232 50.8350833674 -0.7232070255 +7233 50.8331270285 -0.726808746 +7234 50.8313841667 -0.7306740278 +7235 50.8191 -0.7139638889 +7236 50.8249722222 -0.7032166667 +7237 50.8688513007 -0.2972222222 +7238 50.8686747043 -0.3026323425 +7239 50.8681467909 -0.3079849926 +7240 50.8672731683 -0.3132233168 +7241 50.866063116 -0.3182916812 +7242 50.8645294861 -0.3231362684 +7243 50.8626885662 -0.3277056511 +7244 50.8605599052 -0.3319513412 +7245 50.8581661049 -0.3358283055 +7246 50.8555325783 -0.3392954441 +7247 50.8526872793 -0.3423160267 +7248 50.8496604042 -0.3448580805 +7249 50.8464840704 -0.3468947274 +7250 50.8431919744 -0.348404466 +7251 50.8398190339 -0.3493713957 +7252 50.8364010162 -0.3497853811 +7253 50.8329741592 -0.3496421542 +7254 50.8295747861 -0.3489433551 +7255 50.8262389215 -0.347696509 +7256 50.8230019092 -0.3459149416 +7257 50.8198980385 -0.3436176333 +7258 50.8169601818 -0.340829014 +7259 50.8142194473 -0.3375787007 +7260 50.8117048508 -0.3339011814 +7261 50.8094430095 -0.329835448 +7262 50.8074578615 -0.3254245824 +7263 50.8057704138 -0.3207153007 +7264 50.804398521 -0.3157574598 +7265 50.8033566975 -0.3106035313 +7266 50.8026559648 -0.305308049 +7267 50.8023037355 -0.2999270348 +7268 50.8023037355 -0.2945174097 +7269 50.8026559648 -0.2891363954 +7270 50.8033566975 -0.2838409131 +7271 50.804398521 -0.2786869846 +7272 50.8057704138 -0.2737291437 +7273 50.8074578615 -0.2690198621 +7274 50.8094430095 -0.2646089964 +7275 50.8117048508 -0.260543263 +7276 50.8142194473 -0.2568657438 +7277 50.8169601818 -0.2536154305 +7278 50.8198980385 -0.2508268112 +7279 50.8230019092 -0.2485295029 +7280 50.8262389215 -0.2467479354 +7281 50.8295747861 -0.2455010893 +7282 50.8329741592 -0.2448022902 +7283 50.8364010162 -0.2446590634 +7284 50.8398190339 -0.2450730487 +7285 50.8431919744 -0.2460399785 +7286 50.8464840704 -0.2475497171 +7287 50.8496604042 -0.249586364 +7288 50.8526872793 -0.2521284177 +7289 50.8555325783 -0.2551490003 +7290 50.8581661049 -0.258616139 +7291 50.8605599052 -0.2624931032 +7292 50.8626885662 -0.2667387934 +7293 50.8645294861 -0.2713081761 +7294 50.866063116 -0.2761527632 +7295 50.8672731683 -0.2812211277 +7296 50.8681467909 -0.2864594519 +7297 50.8686747043 -0.291812102 +7298 50.8688513007 -0.2972222222 +7299 50.7893027778 -0.3185777778 +7300 50.8032385556 -0.3098738056 +7301 50.8040923247 -0.3144202236 +7302 50.8052022003 -0.3188268489 +7303 50.8065591389 -0.3230578611 +7304 50.7926138889 -0.3317638889 +7305 50.7893027778 -0.3185777778 +7306 50.8825166667 -0.2755388889 +7307 50.8678939167 -0.2846998611 +7308 50.8670472756 -0.2801439923 +7309 50.865943994 -0.2757274932 +7310 50.8645930833 -0.2714863889 +7311 50.8792055556 -0.2623277778 +7312 50.8825166667 -0.2755388889 +7313 50.7904222222 -0.3169555556 +7314 50.80311575 -0.3090648333 +7315 50.8039237264 -0.3136313441 +7316 50.8049890836 -0.3180645222 +7317 50.8063031667 -0.3223283333 +7318 50.7937194444 -0.3301472222 +7319 50.7904222222 -0.3169555556 +7320 50.8823888889 -0.2749555556 +7321 50.8677914722 -0.2840571944 +7322 50.8669086685 -0.2795191306 +7323 50.8657704377 -0.2751254908 +7324 50.8643860556 -0.2709121111 +7325 50.8790916667 -0.2617388889 +7326 50.8823888889 -0.2749555556 +7327 50.8094305556 -0.3579972222 +7328 50.8154169167 -0.3390849167 +7329 50.8178920876 -0.3417847915 +7330 50.8205114974 -0.3441212182 +7331 50.8232537778 -0.3460750833 +7332 50.817475 -0.3643305556 +7333 50.8094305556 -0.3579972222 +7334 50.8599916667 -0.2297 +7335 50.8528699444 -0.2523026944 +7336 50.8502315888 -0.2500184701 +7337 50.8474734479 -0.2481200116 +7338 50.8446180556 -0.2466227778 +7339 50.8519472222 -0.2233611111 +7340 50.8599916667 -0.2297 +7341 50.8602972222 -0.3568833333 +7342 50.8535313333 -0.3414891667 +7343 50.8559970128 -0.3387353645 +7344 50.8582945513 -0.3356396771 +7345 50.8604050278 -0.3322275556 +7346 50.8676777778 -0.3487722222 +7347 50.8602972222 -0.3568833333 +7348 50.8142416667 -0.2274555556 +7349 50.8234243611 -0.2482630278 +7350 50.8206661153 -0.250200315 +7351 50.8180303055 -0.2525237726 +7352 50.8155385833 -0.2552142778 +7353 50.8068638889 -0.2355555556 +7354 50.8142416667 -0.2274555556 +7355 50.9894700535 0.93915 +7356 50.9892934602 0.93372587 +7357 50.9887655562 0.9283593595 +7358 50.9878919491 0.923107472 +7359 50.9866819185 0.9180259857 +7360 50.9851483162 0.9131688582 +7361 50.9833074298 0.9085876498 +7362 50.981178808 0.9043309744 +7363 50.9787850521 0.900443982 +7364 50.9761515751 0.8969678786 +7365 50.9733063304 0.8939394896 +7366 50.9702795138 0.8913908701 +7367 50.9671032423 0.8893489674 +7368 50.9638112119 0.8878353379 +7369 50.9604383396 0.8868659227 +7370 50.9570203922 0.886450883 +7371 50.9535936066 0.8865944969 +7372 50.9501943055 0.8872951194 +7373 50.9468585126 0.8885452053 +7374 50.9436215708 0.8903313938 +7375 50.9405177686 0.8926346547 +7376 50.9375799776 0.8954304945 +7377 50.9348393051 0.8986892193 +7378 50.932324766 0.9023762517 +7379 50.9300629769 0.9064524989 +7380 50.9280778751 0.9108747678 +7381 50.926390467 0.9155962214 +7382 50.9250186065 0.9205668744 +7383 50.9239768078 0.92573412 +7384 50.9232760917 0.9310432838 +7385 50.9229238708 0.9364381998 +7386 50.9229238708 0.9418618002 +7387 50.9232760917 0.9472567162 +7388 50.9239768078 0.95256588 +7389 50.9250186065 0.9577331256 +7390 50.926390467 0.9627037786 +7391 50.9280778751 0.9674252322 +7392 50.9300629769 0.9718475011 +7393 50.932324766 0.9759237483 +7394 50.9348393051 0.9796107807 +7395 50.9375799776 0.9828695055 +7396 50.9405177686 0.9856653453 +7397 50.9436215708 0.9879686062 +7398 50.9468585126 0.9897547947 +7399 50.9501943055 0.9910048806 +7400 50.9535936066 0.9917055031 +7401 50.9570203922 0.991849117 +7402 50.9604383396 0.9914340773 +7403 50.9638112119 0.9904646621 +7404 50.9671032423 0.9889510326 +7405 50.9702795138 0.9869091299 +7406 50.9733063304 0.9843605104 +7407 50.9761515751 0.9813321214 +7408 50.9787850521 0.977856018 +7409 50.981178808 0.9739690256 +7410 50.9833074298 0.9697123502 +7411 50.9851483162 0.9651311418 +7412 50.9866819185 0.9602740143 +7413 50.9878919491 0.955192528 +7414 50.9887655562 0.9499406405 +7415 50.9892934602 0.94457413 +7416 50.9894700535 0.93915 +7417 50.9102333333 0.9009277778 +7418 50.9259866667 0.9169214722 +7419 50.927375169 0.9127054288 +7420 50.9289980997 0.9087043516 +7421 50.93084225 0.9049507778 +7422 50.9150916667 0.8889638889 +7423 50.9102333333 0.9009277778 +7424 51.0018333333 0.9771694444 +7425 50.9863595278 0.9614053611 +7426 50.9849693767 0.9656253748 +7427 50.9833446153 0.9696293844 +7428 50.9814985 0.97338475 +7429 50.996975 0.9891555556 +7430 51.0018333333 0.9771694444 +7431 60.2251892731 -1.2436111111 +7432 60.2250128939 -1.25048308 +7433 60.2244856317 -1.2572819849 +7434 60.2236130921 -1.2639355456 +7435 60.2224045513 -1.2703730408 +7436 60.2208728561 -1.2765260659 +7437 60.2190342866 -1.2823292652 +7438 60.2169083816 -1.2877210302 +7439 60.2145177293 -1.2926441565 +7440 60.2118877258 -1.2970464527 +7441 60.2090463035 -1.3008812932 +7442 60.2060236326 -1.3041081112 +7443 60.2028517994 -1.3066928252 +7444 60.1995644641 -1.3086081946 +7445 60.1961965024 -1.3098341021 +7446 60.1927836347 -1.3103577589 +7447 60.1893620465 -1.3101738317 +7448 60.1859680046 -1.3092844896 +7449 60.1826374726 -1.3076993726 +7450 60.1794057306 -1.3054354794 +7451 60.176307002 -1.30251698 +7452 60.1733740921 -1.2989749513 +7453 60.1706380425 -1.2948470426 +7454 60.1681278037 -1.2901770716 +7455 60.1658699305 -1.2850145576 +7456 60.1638883032 -1.2794141959 +7457 60.162203876 -1.2734352793 +7458 60.1608344578 -1.2671410726 +7459 60.1597945248 -1.2605981468 +7460 60.1590950691 -1.2538756796 +7461 60.1587434834 -1.2470447298 +7462 60.1587434834 -1.2401774924 +7463 60.1590950691 -1.2333465426 +7464 60.1597945248 -1.2266240754 +7465 60.1608344578 -1.2200811496 +7466 60.162203876 -1.2137869429 +7467 60.1638883032 -1.2078080264 +7468 60.1658699305 -1.2022076647 +7469 60.1681278037 -1.1970451506 +7470 60.1706380425 -1.1923751796 +7471 60.1733740921 -1.1882472709 +7472 60.176307002 -1.1847052422 +7473 60.1794057306 -1.1817867428 +7474 60.1826374726 -1.1795228496 +7475 60.1859680046 -1.1779377326 +7476 60.1893620465 -1.1770483906 +7477 60.1927836347 -1.1768644633 +7478 60.1961965024 -1.1773881202 +7479 60.1995644641 -1.1786140277 +7480 60.2028517994 -1.180529397 +7481 60.2060236326 -1.183114111 +7482 60.2090463035 -1.1863409291 +7483 60.2118877258 -1.1901757695 +7484 60.2145177293 -1.1945780657 +7485 60.2169083816 -1.1995011921 +7486 60.2190342866 -1.204892957 +7487 60.2208728561 -1.2106961563 +7488 60.2224045513 -1.2168491815 +7489 60.2236130921 -1.2232866766 +7490 60.2244856317 -1.2299402373 +7491 60.2250128939 -1.2367391422 +7492 60.2251892731 -1.2436111111 +7493 60.1442333333 -1.2567777778 +7494 60.1588478889 -1.2499103611 +7495 60.1592652753 -1.2558708651 +7496 60.1599485109 -1.2617318323 +7497 60.1608920556 -1.2674456667 +7498 60.1462833333 -1.2743027778 +7499 60.1442333333 -1.2567777778 +7500 60.2400916667 -1.2301611111 +7501 60.22503875 -1.2372617778 +7502 60.2246189182 -1.2312903432 +7503 60.2239327561 -1.2254195327 +7504 60.2229858889 -1.2196972778 +7505 60.2380444444 -1.2125861111 +7506 60.2400916667 -1.2301611111 +7507 50.5194 -3.655 +7508 50.513475 -3.6629972222 +7509 50.5095444444 -3.6626555556 +7510 50.5061305556 -3.6555166667 +7511 50.5079861111 -3.6463638889 +7512 50.5149527778 -3.6433027778 +7513 50.5187722222 -3.6451 +7514 50.5194 -3.655 +7515 50.5549111111 -3.9961305556 +7516 50.5521527778 -4.0056361111 +7517 50.5430111111 -3.9991277778 +7518 50.5463833333 -3.9899416667 +7519 50.5496972222 -3.9880027778 +7520 50.5534277778 -3.9904138889 +7521 50.5549111111 -3.9961305556 +7522 50.7332972222 -3.5325777778 +7523 50.731125 -3.5415472222 +7524 50.7234888889 -3.5382944444 +7525 50.7256 -3.5232972222 +7526 50.7326305556 -3.526575 +7527 50.7332972222 -3.5325777778 +7528 50.9901722222 -2.2236361111 +7529 50.9858083333 -2.2300527778 +7530 50.9782111111 -2.2209777778 +7531 50.9837472222 -2.2080888889 +7532 50.9911916667 -2.2145111111 +7533 50.9901722222 -2.2236361111 +7534 50.7187833333 -1.3200083333 +7535 50.7045388889 -1.3110416667 +7536 50.7075833333 -1.2973027778 +7537 50.7215638889 -1.3026555556 +7538 50.7187833333 -1.3200083333 +7539 50.8787138889 -0.0049527778 +7540 50.874425 -0.01605 +7541 50.8666 -0.0089611111 +7542 50.8709777778 0.00205 +7543 50.8752805556 0.0016305556 +7544 50.8787138889 -0.0049527778 +7545 50.5564944444 -2.430325 +7546 50.5517 -2.43215 +7547 50.5452805556 -2.4248138889 +7548 50.5464833333 -2.4123027778 +7549 50.5516916667 -2.4152 +7550 50.55705 -2.4202333333 +7551 50.5564944444 -2.430325 +7552 50.5662944444 -2.4375472222 +7553 50.5640555556 -2.4433861111 +7554 50.5574805556 -2.4445305556 +7555 50.5572861111 -2.4380888889 +7556 50.5555277778 -2.4366027778 +7557 50.5591222222 -2.4245555556 +7558 50.5659888889 -2.4293055556 +7559 50.5662944444 -2.4375472222 +7560 51.866601154 -4.9608472222 +7561 51.8664245833 -4.9663762085 +7562 51.8658967469 -4.9718464575 +7563 51.8650232521 -4.97719986 +7564 51.8638133777 -4.9823795559 +7565 51.8622799751 -4.9873305421 +7566 51.8604393304 -4.9920002595 +7567 51.8583109909 -4.9963391531 +7568 51.8559175563 -5.0003012001 +7569 51.8532844373 -5.0038443986 +7570 51.8504395846 -5.0069312133 +7571 51.8474131912 -5.0095289721 +7572 51.8442373706 -5.0116102105 +7573 51.8409458148 -5.0131529595 +7574 51.8375734365 -5.0141409747 +7575 51.8341559975 -5.0145639039 +7576 51.8307297297 -5.0144173916 +7577 51.8273309503 -5.0137031196 +7578 51.8239956769 -5.0124287842 +7579 51.8207592466 -5.010608009 +7580 51.8176559415 -5.0082601956 +7581 51.8147186271 -5.0054103137 +7582 51.8119784046 -5.0020886333 +7583 51.8094642829 -4.9983304008 +7584 51.8072028728 -4.9941754641 +7585 51.8052181066 -4.9896678499 +7586 51.8035309858 -4.9848552974 +7587 51.8021593605 -4.9797887545 +7588 51.8011177411 -4.9745218403 +7589 51.8004171461 -4.9691102802 +7590 51.8000649862 -4.9636113201 +7591 51.8000649862 -4.9580831243 +7592 51.8004171461 -4.9525841643 +7593 51.8011177411 -4.9471726042 +7594 51.8021593605 -4.9419056899 +7595 51.8035309858 -4.9368391471 +7596 51.8052181066 -4.9320265946 +7597 51.8072028728 -4.9275189803 +7598 51.8094642829 -4.9233640436 +7599 51.8119784046 -4.9196058111 +7600 51.8147186271 -4.9162841307 +7601 51.8176559415 -4.9134342489 +7602 51.8207592466 -4.9110864354 +7603 51.8239956769 -4.9092656602 +7604 51.8273309503 -4.9079913248 +7605 51.8307297297 -4.9072770529 +7606 51.8341559975 -4.9071305405 +7607 51.8375734365 -4.9075534697 +7608 51.8409458148 -4.908541485 +7609 51.8442373706 -4.9100842339 +7610 51.8474131912 -4.9121654723 +7611 51.8504395846 -4.9147632311 +7612 51.8532844373 -4.9178500458 +7613 51.8559175563 -4.9213932444 +7614 51.8583109909 -4.9253552913 +7615 51.8604393304 -4.929694185 +7616 51.8622799751 -4.9343639023 +7617 51.8638133777 -4.9393148885 +7618 51.8650232521 -4.9444945845 +7619 51.8658967469 -4.9498479869 +7620 51.8664245833 -4.9553182359 +7621 51.866601154 -4.9608472222 +7622 51.7878444444 -4.9943083333 +7623 51.8024292222 -4.9809063333 +7624 51.8036751517 -4.9853153742 +7625 51.8051622529 -4.9895255747 +7626 51.8068784444 -4.9935026944 +7627 51.7922972222 -5.0068972222 +7628 51.7878444444 -4.9943083333 +7629 51.8785055556 -4.9275583333 +7630 51.8641889167 -4.9407586667 +7631 51.8629411724 -4.9363448359 +7632 51.8614520004 -4.9321309303 +7633 51.8597335556 -4.9281513056 +7634 51.8740527778 -4.9149444444 +7635 51.8785055556 -4.9275583333 +7636 51.8277361111 -5.0394888889 +7637 51.8284296389 -5.0139970278 +7638 51.8314198647 -5.0144928085 +7639 51.8344256075 -5.0145512565 +7640 51.8374223611 -5.0141718056 +7641 51.8367166667 -5.0401138889 +7642 51.8277361111 -5.0394888889 +7643 51.8408111111 -4.886525 +7644 51.8402431944 -4.9082875833 +7645 51.8372777002 -4.9074941979 +7646 51.8342799592 -4.9071359293 +7647 51.8312744167 -4.9072156111 +7648 51.8318305556 -4.8859027778 +7649 51.8408111111 -4.886525 +7650 51.6385691199 -4.0677777778 +7651 51.6383925433 -4.0732789905 +7652 51.6378646894 -4.0787217619 +7653 51.6369911656 -4.0840482758 +7654 51.6357812508 -4.0892019586 +7655 51.6342477966 -4.0941280843 +7656 51.6324070894 -4.0987743581 +7657 51.6302786768 -4.1030914745 +7658 51.6278851591 -4.1070336417 +7659 51.6252519474 -4.1105590688 +7660 51.6224069933 -4.1136304084 +7661 51.6193804903 -4.1162151518 +7662 51.6162045529 -4.1182859716 +7663 51.6129128741 -4.1198210079 +7664 51.6095403677 -4.1208040969 +7665 51.606122797 -4.1212249367 +7666 51.6026963949 -4.1210791924 +7667 51.5992974802 -4.120368536 +7668 51.595962072 -4.1191006239 +7669 51.592725509 -4.1172890099 +7670 51.5896220749 -4.1149529973 +7671 51.5866846367 -4.1121174298 +7672 51.5839442973 -4.1088124245 +7673 51.5814300673 -4.1050730509 +7674 51.5791685587 -4.1009389566 +7675 51.5771837053 -4.0964539477 +7676 51.5754965099 -4.0916655245 +7677 51.5741248235 -4.0866243798 +7678 51.5730831575 -4.0813838645 +7679 51.572382531 -4.0759994259 +7680 51.5720303553 -4.0705280237 +7681 51.5720303553 -4.0650275318 +7682 51.572382531 -4.0595561297 +7683 51.5730831575 -4.054171691 +7684 51.5741248235 -4.0489311758 +7685 51.5754965099 -4.0438900311 +7686 51.5771837053 -4.0391016078 +7687 51.5791685587 -4.0346165989 +7688 51.5814300673 -4.0304825047 +7689 51.5839442973 -4.026743131 +7690 51.5866846367 -4.0234381258 +7691 51.5896220749 -4.0206025582 +7692 51.592725509 -4.0182665456 +7693 51.595962072 -4.0164549317 +7694 51.5992974802 -4.0151870195 +7695 51.6026963949 -4.0144763632 +7696 51.606122797 -4.0143306189 +7697 51.6095403677 -4.0147514587 +7698 51.6129128741 -4.0157345476 +7699 51.6162045529 -4.017269584 +7700 51.6193804903 -4.0193404037 +7701 51.6224069933 -4.0219251472 +7702 51.6252519474 -4.0249964868 +7703 51.6278851591 -4.0285219138 +7704 51.6302786768 -4.0324640811 +7705 51.6324070894 -4.0367811974 +7706 51.6342477966 -4.0414274713 +7707 51.6357812508 -4.0463535969 +7708 51.6369911656 -4.0515072798 +7709 51.6378646894 -4.0568337937 +7710 51.6383925433 -4.0622765651 +7711 51.6385691199 -4.0677777778 +7712 51.5614305556 -4.1105694444 +7713 51.5760447778 -4.0933516667 +7714 51.5775992074 -4.0974772875 +7715 51.5793789018 -4.1013615228 +7716 51.5813693889 -4.1049727778 +7717 51.5667527778 -4.1221888889 +7718 51.5614305556 -4.1105694444 +7719 51.6483027778 -4.0259555556 +7720 51.6345286389 -4.0422406389 +7721 51.632975828 -4.0381074205 +7722 51.631197314 -4.0342163026 +7723 51.6292076111 -4.030599 +7724 51.6429805556 -4.0143111111 +7725 51.6483027778 -4.0259555556 +7726 51.6016305556 -4.1483194444 +7727 51.5997253611 -4.1204896111 +7728 51.602737017 -4.1210842429 +7729 51.605769878 -4.1212361072 +7730 51.60879875 -4.1209438611 +7731 51.6105638889 -4.1467305556 +7732 51.6016305556 -4.1483194444 +7733 51.5998777778 -3.9918916667 +7734 51.6014628333 -4.0146683056 +7735 51.5984676719 -4.015448363 +7736 51.5955291688 -4.0166629251 +7737 51.5926717222 -4.0183018333 +7738 51.5909444444 -3.9934777778 +7739 51.5998777778 -3.9918916667 +7740 51.4255555556 -3.3911111111 +7741 51.4281636406 -3.3947277475 +7742 51.4305415517 -3.3987267963 +7743 51.4326475738 -3.4030987649 +7744 51.4344590111 -3.4077965855 +7745 51.4359563401 -3.4127696603 +7746 51.4371234209 -3.4179644073 +7747 51.4379476723 -3.4233248408 +7748 51.4384202082 -3.4287931779 +7749 51.4385359342 -3.4343104649 +7750 51.4382936026 -3.4398172168 +7751 51.437695826 -3.445254063 +7752 51.4367490491 -3.4505623917 +7753 51.4354634786 -3.4556849849 +7754 51.4338529727 -3.4605666395 +7755 51.4319348906 -3.465154765 +7756 51.4297299043 -3.4693999519 +7757 51.4272617751 -3.4732565058 +7758 51.4245570954 -3.4766829403 +7759 51.4216450019 -3.4796424223 +7760 51.4185568596 -3.4821031677 +7761 51.4153259234 -3.4840387809 +7762 51.4119869789 -3.4854285349 +7763 51.4085759665 -3.4862575909 +7764 51.4051295947 -3.4865171524 +7765 51.4016849442 -3.4862045549 +7766 51.3982790688 -3.4853232893 +7767 51.3949485973 -3.4838829581 +7768 51.3917293395 -3.4818991679 +7769 51.3886559024 -3.4793933557 +7770 51.3857613184 -3.4763925551 +7771 51.3830766918 -3.4729291017 +7772 51.3806308656 -3.4690402832 +7773 51.3784501128 -3.4647679371 +7774 51.3765578554 -3.4601580005 +7775 51.3749744143 -3.4552600171 +7776 51.3737167921 -3.4501266063 +7777 51.3727984916 -3.4448129005 +7778 51.3722293717 -3.4393759557 +7779 51.3720155421 -3.4338741428 +7780 51.3721592983 -3.4283665243 +7781 51.3726590972 -3.4229122247 +7782 51.3735095732 -3.4175698 +7783 51.3747015956 -3.4123966127 +7784 51.3762223661 -3.4074482194 +7785 51.3780555556 -3.4027777778 +7786 51.4255555556 -3.3911111111 +7787 51.3855 -3.5119361111 +7788 51.3912958056 -3.4816345 +7789 51.3940757942 -3.483453917 +7790 51.3969470432 -3.4848655896 +7791 51.3998861944 -3.4858579444 +7792 51.3940972222 -3.5161222222 +7793 51.3855 -3.5119361111 +7794 51.424925 -3.3543944444 +7795 51.4175764444 -3.3930726111 +7796 51.4077211111 -3.3954943889 +7797 51.4163277778 -3.3502 +7798 51.424925 -3.3543944444 +7799 51.4255555556 -3.3911111111 +7800 51.3780555556 -3.4027777778 +7801 51.3747004374 -3.3998652394 +7802 51.3715489884 -3.3964158735 +7803 51.3686086909 -3.3925197597 +7804 51.3659042849 -3.3882097622 +7805 51.3634585212 -3.3835222082 +7806 51.3612919717 -3.3784965819 +7807 51.3594228567 -3.3731751922 +7808 51.3578668934 -3.367602818 +7809 51.356637164 -3.3618263334 +7810 51.3557440071 -3.3558943152 +7811 51.355194931 -3.3498566379 +7812 51.3549945514 -3.3437640568 +7813 51.3551445526 -3.337667785 +7814 51.3556436737 -3.3316190667 +7815 51.3564877191 -3.3256687493 +7816 51.3576695933 -3.3198668596 +7817 51.3591793603 -3.3142621866 +7818 51.3610043263 -3.3089018737 +7819 51.3631291457 -3.303831025 +7820 51.3655359494 -3.2990923271 +7821 51.3682044938 -3.2947256915 +7822 51.3711123302 -3.2907679193 +7823 51.3742349926 -3.2872523906 +7824 51.377546202 -3.284208783 +7825 51.3810180874 -3.2816628197 +7826 51.3846214184 -3.2796360502 +7827 51.3883258514 -3.2781456658 +7828 51.392100184 -3.277204351 +7829 51.3959126172 -3.2768201726 +7830 51.3997310233 -3.2769965071 +7831 51.4035232161 -3.2777320074 +7832 51.4072572226 -3.27902061 +7833 51.4109015527 -3.2808515811 +7834 51.4144254654 -3.283209603 +7835 51.4177992282 -3.2860748989 +7836 51.4209943694 -3.2894233972 +7837 51.4239839189 -3.2932269306 +7838 51.4267426368 -3.2974534725 +7839 51.4292472279 -3.3020674054 +7840 51.4314765391 -3.3070298211 +7841 51.4334117396 -3.3122988491 +7842 51.4350364804 -3.3178300112 +7843 51.4363370339 -3.3235765985 +7844 51.4373024107 -3.3294900682 +7845 51.4379244528 -3.3355204563 +7846 51.4381979032 -3.341616803 +7847 51.4381204511 -3.3477275864 +7848 51.437692751 -3.3538011618 +7849 51.4369184174 -3.3597862013 +7850 51.435803994 -3.3656321314 +7851 51.4343588982 -3.3712895632 +7852 51.4325953402 -3.3767107132 +7853 51.4305282199 -3.3818498086 +7854 51.4281749996 -3.3866634765 +7855 51.4255555556 -3.3911111111 +7856 51.4166861111 -3.4230194444 +7857 51.4079994167 -3.395426 +7858 51.4173411111 -3.3931304444 +7859 51.4247111111 -3.4165416667 +7860 51.4166861111 -3.4230194444 +7861 51.3761972222 -3.2628444444 +7862 51.3819633056 -3.2810616111 +7863 51.3791942869 -3.2829113154 +7864 51.3765158529 -3.2850748667 +7865 51.3739419167 -3.2875409722 +7866 51.3681722222 -3.2693111111 +7867 51.3761972222 -3.2628444444 +7868 51.4242851807 -2.7191 +7869 51.4241074951 -2.725241868 +7870 51.4235759583 -2.731331194 +7871 51.4226951174 -2.7373158889 +7872 51.421472507 -2.7431447661 +7873 51.4199185848 -2.7487679819 +7874 51.4180466408 -2.7541374654 +7875 51.4158726835 -2.7592073311 +7876 51.4134153014 -2.7639342736 +7877 51.4106955036 -2.7682779384 +7878 51.4077365385 -2.772201267 +7879 51.4045636943 -2.7756708136 +7880 51.4012040819 -2.7786570288 +7881 51.3976864016 -2.7811345104 +7882 51.3940406978 -2.7830822176 +7883 51.3902981006 -2.7844836469 +7884 51.3864905603 -2.7853269691 +7885 51.3826505733 -2.7856051262 +7886 51.3788109052 -2.7853158864 +7887 51.3750043104 -2.7844618587 +7888 51.3712632532 -2.7830504661 +7889 51.3676196314 -2.7810938767 +7890 51.3641045045 -2.7786088966 +7891 51.3607478295 -2.7756168221 +7892 51.357578207 -2.7721432548 +7893 51.3546226381 -2.7682178809 +7894 51.3519062952 -2.7638742162 +7895 51.3494523093 -2.7591493189 +7896 51.3472815737 -2.7540834738 +7897 51.3454125672 -2.7487198497 +7898 51.3438611982 -2.7431041323 +7899 51.3426406699 -2.7372841373 +7900 51.341761369 -2.7313094058 +7901 51.3412307778 -2.7252307852 +7902 51.341053411 -2.7191 +7903 51.3412307778 -2.7129692148 +7904 51.341761369 -2.7068905942 +7905 51.3426406699 -2.7009158627 +7906 51.3438611982 -2.6950958677 +7907 51.3454125672 -2.6894801503 +7908 51.3472815737 -2.6841165262 +7909 51.3494523093 -2.6790506811 +7910 51.3519062952 -2.6743257838 +7911 51.3546226381 -2.6699821191 +7912 51.357578207 -2.6660567452 +7913 51.3607478295 -2.6625831779 +7914 51.3641045045 -2.6595911034 +7915 51.3676196314 -2.6571061233 +7916 51.3712632532 -2.6551495339 +7917 51.3750043104 -2.6537381413 +7918 51.3788109052 -2.6528841136 +7919 51.3826505733 -2.6525948738 +7920 51.3864905603 -2.6528730309 +7921 51.3902981006 -2.6537163531 +7922 51.3940406978 -2.6551177824 +7923 51.3976864016 -2.6570654896 +7924 51.4012040819 -2.6595429712 +7925 51.4045636943 -2.6625291864 +7926 51.4077365385 -2.665998733 +7927 51.4106955036 -2.6699220616 +7928 51.4134153014 -2.6742657264 +7929 51.4158726835 -2.6789926689 +7930 51.4180466408 -2.6840625346 +7931 51.4199185848 -2.6894320181 +7932 51.421472507 -2.6950552339 +7933 51.4226951174 -2.7008841111 +7934 51.4235759583 -2.706868806 +7935 51.4241074951 -2.712958132 +7936 51.4242851807 -2.7191 +7937 51.3748027778 -2.8047333333 +7938 51.3755981944 -2.784633 +7939 51.3785715963 -2.7852789747 +7940 51.3815663965 -2.785580968 +7941 51.3845670278 -2.7855373333 +7942 51.3837722222 -2.8056222222 +7943 51.3748027778 -2.8047333333 +7944 51.3904027778 -2.6352888889 +7945 51.389704 -2.6535468333 +7946 51.3867298164 -2.6529092331 +7947 51.3837346154 -2.6526158735 +7948 51.3807339722 -2.6526682222 +7949 51.3814333333 -2.6343944444 +7950 51.3904027778 -2.6352888889 +7951 50.9714693611 -2.6762913333 +7952 50.967843 -2.6298215278 +7953 50.9689304403 -2.6239672815 +7954 50.9703547957 -2.618297061 +7955 50.9721039029 -2.6128593738 +7956 50.974162805 -2.6077007473 +7957 50.9765138932 -2.6028653391 +7958 50.9791370573 -2.5983945605 +7959 50.9820098563 -2.594326723 +7960 50.9851077091 -2.5906967097 +7961 50.9884041042 -2.5875356765 +7962 50.991870825 -2.5848707832 +7963 50.9954781906 -2.5827249586 +7964 50.9991953089 -2.581116701 +7965 51.0029903407 -2.5800599161 +7966 51.0068307715 -2.5795637937 +7967 51.0106836897 -2.5796327246 +7968 51.0145160689 -2.5802662577 +7969 51.0182950504 -2.5814590998 +7970 51.0219882257 -2.5832011558 +7971 51.0255639143 -2.5854776109 +7972 51.0289914368 -2.5882690536 +7973 51.0322413781 -2.5915516385 +7974 51.0352858415 -2.5952972881 +7975 51.0380986885 -2.5994739312 +7976 51.0406557648 -2.6040457767 +7977 51.0429351086 -2.60897362 +7978 51.0449171406 -2.6142151797 +7979 51.0465848329 -2.6197254613 +7980 51.0479238563 -2.6254571452 +7981 51.0489227048 -2.6313609955 +7982 51.0495727947 -2.6373862853 +7983 51.049868539 -2.643481236 +7984 51.0498073961 -2.6495934654 +7985 51.0493898914 -2.6556704418 +7986 51.0486196131 -2.6616599388 +7987 51.0475031808 -2.6675104878 +7988 51.0460501886 -2.6731718236 +7989 51.0442731215 -2.6785953191 +7990 51.0421872477 -2.6837344058 +7991 51.0398104864 -2.6885449756 +7992 51.0371632529 -2.6929857609 +7993 51.0342682818 -2.6970186893 +7994 51.0311504313 -2.7006092105 +7995 51.0278364679 -2.7037265914 +7996 51.0243548361 -2.7063441786 +7997 51.0207354127 -2.708439624 +7998 51.0170092504 -2.7099950736 +7999 51.0132083097 -2.7109973165 +8000 51.0093651849 -2.7114378947 +8001 51.0055128239 -2.7113131703 +8002 51.0016842458 -2.7106243521 +8003 50.9979122577 -2.7093774809 +8004 50.994229174 -2.7075833724 +8005 50.9906665399 -2.7052575206 +8006 50.9872548621 -2.7024199611 +8007 50.9840233479 -2.6990950954 +8008 50.9809996566 -2.6953114796 +8009 50.9782096634 -2.6911015776 +8010 50.9756772394 -2.6865014817 +8011 50.9734240479 -2.6815506027 +8012 50.9714693611 -2.6762913333 +8013 50.9650763611 -2.6813681667 +8014 50.9712873611 -2.6739531389 +8015 50.9714693611 -2.6762913333 +8016 50.9734295096 -2.6815638587 +8017 50.9756896667 -2.6865262778 +8018 50.9704911944 -2.6927310556 +8019 50.9650763611 -2.6813681667 +8020 51.0527433889 -2.5943472222 +8021 51.0421141111 -2.6070863889 +8022 51.0402731247 -2.6033052479 +8023 51.0382644429 -2.5997455139 +8024 51.0360986111 -2.5964258333 +8025 51.0473286111 -2.5829642222 +8026 51.0527433889 -2.5943472222 +8027 50.9971264722 -2.7315610556 +8028 50.9988129167 -2.7097279722 +8029 51.0017583572 -2.7106431331 +8030 51.0047377531 -2.7112195574 +8031 51.0077356111 -2.7114541944 +8032 51.0060498889 -2.7332775556 +8033 50.9971264722 -2.7315610556 +8034 51.019364 -2.5594051667 +8035 51.017707 -2.5812353056 +8036 51.0147607937 -2.5803261568 +8037 51.0117809128 -2.5797560879 +8038 51.0087828611 -2.579528 +8039 51.0104406111 -2.5576881667 +8040 51.019364 -2.5594051667 +8041 51.1519444444 1.3683333333 +8042 51.1155555556 1.2641666667 +8043 51.1125068064 1.2672038795 +8044 51.1096190712 1.270605115 +8045 51.1069497853 1.2744300642 +8046 51.1045235011 1.2786434752 +8047 51.1023625326 1.2832065412 +8048 51.1004867505 1.2880772581 +8049 51.098913401 1.2932108101 +8050 51.0976569483 1.2985599804 +8051 51.096728942 1.304075583 +8052 51.096137912 1.309706913 +8053 51.0958892907 1.3154022092 +8054 51.095985363 1.3211091266 +8055 51.096425246 1.3267752144 +8056 51.0972048968 1.3323483941 +8057 51.0983171491 1.3377774353 +8058 51.0997517792 1.3430124231 +8059 51.1014955989 1.3480052141 +8060 51.1035325759 1.3527098772 +8061 51.1058439808 1.357083114 +8062 51.1084085577 1.3610846561 +8063 51.1112027189 1.3646776353 +8064 51.1142007606 1.3678289231 +8065 51.1173750984 1.3705094373 +8066 51.1206965203 1.3726944115 +8067 51.1241344542 1.3743636256 +8068 51.1276572486 1.375501596 +8069 51.1312324636 1.3760977216 +8070 51.1348271693 1.3761463859 +8071 51.1384082484 1.3756470134 +8072 51.1419427016 1.3746040794 +8073 51.1453979519 1.3730270737 +8074 51.1487421452 1.3709304173 +8075 51.1519444444 1.3683333333 +8076 51.9274563633 -2.1672222222 +8077 51.9272797941 -2.172758683 +8078 51.9267519623 -2.1782363268 +8079 51.9258784752 -2.1835969655 +8080 51.9246686117 -2.1887836621 +8081 51.9231352228 -2.1937413388 +8082 51.9212945947 -2.1984173653 +8083 51.9191662747 -2.2027621196 +8084 51.9167728622 -2.2067295166 +8085 51.9141397679 -2.2102774978 +8086 51.9112949423 -2.2133684771 +8087 51.9082685781 -2.2159697386 +8088 51.9050927885 -2.2180537808 +8089 51.9018012655 -2.2195986054 +8090 51.8984289213 -2.2205879463 +8091 51.8950115175 -2.2210114378 +8092 51.8915852855 -2.2208647187 +8093 51.8881865421 -2.2201494737 +8094 51.8848513047 -2.2188734096 +8095 51.8816149097 -2.2170501689 +8096 51.8785116391 -2.2146991796 +8097 51.8755743577 -2.2118454455 +8098 51.8728341663 -2.2085192775 +8099 51.8703200735 -2.2047559697 +8100 51.8680586897 -2.2005954239 +8101 51.8660739467 -2.1960817261 +8102 51.8643868459 -2.19126268 +8103 51.8630152369 -2.186189302 +8104 51.8619736299 -2.1809152833 +8105 51.8612730433 -2.1754964243 +8106 51.8609208876 -2.1699900479 +8107 51.8609208876 -2.1644543965 +8108 51.8612730433 -2.1589480201 +8109 51.8619736299 -2.1535291612 +8110 51.8630152369 -2.1482551424 +8111 51.8643868459 -2.1431817645 +8112 51.8660739467 -2.1383627184 +8113 51.8680586897 -2.1338490206 +8114 51.8703200735 -2.1296884748 +8115 51.8728341663 -2.125925167 +8116 51.8755743577 -2.122598999 +8117 51.8785116391 -2.1197452649 +8118 51.8816149097 -2.1173942755 +8119 51.8848513047 -2.1155710348 +8120 51.8881865421 -2.1142949708 +8121 51.8915852855 -2.1135797258 +8122 51.8950115175 -2.1134330067 +8123 51.8984289213 -2.1138564981 +8124 51.9018012655 -2.1148458391 +8125 51.9050927885 -2.1163906636 +8126 51.9082685781 -2.1184747058 +8127 51.9112949423 -2.1210759673 +8128 51.9141397679 -2.1241669467 +8129 51.9167728622 -2.1277149279 +8130 51.9191662747 -2.1316823249 +8131 51.9212945947 -2.1360270792 +8132 51.9231352228 -2.1407031056 +8133 51.9246686117 -2.1456607824 +8134 51.9258784752 -2.1508474789 +8135 51.9267519623 -2.1562081177 +8136 51.9272797941 -2.1616857614 +8137 51.9274563633 -2.1672222222 +8138 51.8490638889 -2.2033861111 +8139 51.8633313889 -2.1874931944 +8140 51.8645919882 -2.191914972 +8141 51.8660948525 -2.1961347567 +8142 51.8678276944 -2.200118 +8143 51.8541694444 -2.2153277778 +8144 51.8490638889 -2.2033861111 +8145 51.93475 -2.1254277778 +8146 51.9225411667 -2.1390743333 +8147 51.9208495231 -2.1350394219 +8148 51.9189390143 -2.1312688435 +8149 51.9168253333 -2.1277935278 +8150 51.9296444444 -2.1134611111 +8151 51.93475 -2.1254277778 +8152 51.8513694444 -2.1998861111 +8153 51.86313675 -2.1867024167 +8154 51.8643562518 -2.1911634416 +8155 51.8658207904 -2.1954279461 +8156 51.8675183611 -2.1994608889 +8157 51.8564972222 -2.2118055556 +8158 51.8513694444 -2.1998861111 +8159 51.9325694444 -2.1264444444 +8160 51.9221743611 -2.13813 +8161 51.9204284823 -2.1341466733 +8162 51.9184665182 -2.1304358591 +8163 51.9163046389 -2.1270280833 +8164 51.9274444444 -2.1145027778 +8165 51.9325694444 -2.1264444444 +8166 51.8840111111 -2.248525 +8167 51.8860011667 -2.2193798056 +8168 51.8889439051 -2.2203588823 +8169 51.8919292781 -2.2209052777 +8170 51.8949329722 -2.2210144722 +8171 51.8929472222 -2.2501027778 +8172 51.8840111111 -2.248525 +8173 51.9038138889 -2.0895777778 +8174 51.9021101667 -2.1149658333 +8175 51.8991634474 -2.1140228124 +8176 51.8961761338 -2.1135131055 +8177 51.8931725556 -2.1134407778 +8178 51.8948805556 -2.0879944444 +8179 51.9038138889 -2.0895777778 +8180 51.7013520953 -2.0570083333 +8181 51.7011755203 -2.0625171561 +8182 51.7006476712 -2.0679674566 +8183 51.6997741554 -2.0733013381 +8184 51.6985642518 -2.0784621486 +8185 51.6970308118 -2.0833950862 +8186 51.6951901218 -2.0880477837 +8187 51.6930617294 -2.0923708672 +8188 51.6906682346 -2.0963184816 +8189 51.6880350485 -2.0998487782 +8190 51.6851901223 -2.1029243581 +8191 51.6821636495 -2.1055126678 +8192 51.6789877442 -2.1075863423 +8193 51.6756960994 -2.109123492 +8194 51.6723236283 -2.1101079308 +8195 51.6689060938 -2.1105293431 +8196 51.6654797288 -2.1103833884 +8197 51.6620808513 -2.1096717414 +8198 51.6587454803 -2.1084020693 +8199 51.6555089538 -2.1065879451 +8200 51.6524055552 -2.104248699 +8201 51.6494681512 -2.1014092092 +8202 51.646727844 -2.0980996349 +8203 51.6442136437 -2.0943550938 +8204 51.6419521623 -2.0902152886 +8205 51.6399673329 -2.0857240857 +8206 51.6382801581 -2.0809290509 +8207 51.6369084885 -2.0758809469 +8208 51.6358668353 -2.0706331981 +8209 51.6351662175 -2.065241328 +8210 51.6348140461 -2.0597623748 +8211 51.6348140461 -2.0542542919 +8212 51.6351662175 -2.0487753386 +8213 51.6358668353 -2.0433834685 +8214 51.6369084885 -2.0381357198 +8215 51.6382801581 -2.0330876158 +8216 51.6399673329 -2.028292581 +8217 51.6419521623 -2.0238013781 +8218 51.6442136437 -2.0196615729 +8219 51.646727844 -2.0159170318 +8220 51.6494681512 -2.0126074574 +8221 51.6524055552 -2.0097679677 +8222 51.6555089538 -2.0074287216 +8223 51.6587454803 -2.0056145974 +8224 51.6620808513 -2.0043449253 +8225 51.6654797288 -2.0036332783 +8226 51.6689060938 -2.0034873235 +8227 51.6723236283 -2.0039087359 +8228 51.6756960994 -2.0048931747 +8229 51.6789877442 -2.0064303243 +8230 51.6821636495 -2.0085039989 +8231 51.6851901223 -2.0110923086 +8232 51.6880350485 -2.0141678885 +8233 51.6906682346 -2.0176981851 +8234 51.6930617294 -2.0216457995 +8235 51.6951901218 -2.0259688829 +8236 51.6970308118 -2.0306215804 +8237 51.6985642518 -2.035554518 +8238 51.6997741554 -2.0407153286 +8239 51.7006476712 -2.0460492101 +8240 51.7011755203 -2.0514995105 +8241 51.7013520953 -2.0570083333 +8242 51.6548986944 -2.1386894444 +8243 51.6581286111 -2.1081021667 +8244 51.6610331599 -2.1093354747 +8245 51.6639950203 -2.1101428888 +8246 51.6669900833 -2.11051775 +8247 51.6637611389 -2.1410953889 +8248 51.6548986944 -2.1386894444 +8249 51.6811496667 -1.9754756111 +8250 51.6779745556 -2.0058937778 +8251 51.675069011 -2.0046661483 +8252 51.672106485 -2.0038649379 +8253 51.6691111111 -2.0034965833 +8254 51.67228725 -1.97306875 +8255 51.6811496667 -1.9754756111 +8256 51.6566277778 -2.1295 +8257 51.6588605 -2.1084556667 +8258 51.661782657 -2.1095817412 +8259 51.664756054 -2.1102796614 +8260 51.6677564722 -2.1105436667 +8261 51.6654888889 -2.1319166667 +8262 51.6566277778 -2.1295 +8263 51.6813694444 -1.9814111111 +8264 51.6787570556 -2.0063030556 +8265 51.6758704389 -2.0049599261 +8266 51.6729202744 -2.0040410911 +8267 51.6699306111 -2.0035539444 +8268 51.6725083333 -1.9789916667 +8269 51.6813694444 -1.9814111111 +8270 51.7251302571 -1.7900055556 +8271 51.7249525789 -1.7961881038 +8272 51.7244210644 -1.8023177604 +8273 51.7235402605 -1.80834209 +8274 51.7223177018 -1.8142095653 +8275 51.7207638457 -1.8198700117 +8276 51.7188919822 -1.8252750386 +8277 51.7167181193 -1.8303784562 +8278 51.7142608454 -1.8351366718 +8279 51.711541169 -1.8395090636 +8280 51.7085823379 -1.8434583283 +8281 51.7054096398 -1.846950799 +8282 51.7020501846 -1.8499567317 +8283 51.6985326718 -1.8524505575 +8284 51.6948871446 -1.8544110975 +8285 51.691144732 -1.8558217409 +8286 51.6873373829 -1.8566705822 +8287 51.6834975923 -1.8569505185 +8288 51.679658124 -1.8566593054 +8289 51.6758517307 -1.8557995713 +8290 51.6721108749 -1.8543787901 +8291 51.6684674524 -1.8524092124 +8292 51.6649525207 -1.8499077569 +8293 51.6615960349 -1.8468958622 +8294 51.6584265935 -1.8433993005 +8295 51.6554711955 -1.8394479548 +8296 51.6527550116 -1.8350755629 +8297 51.6503011708 -1.8303194283 +8298 51.6481305646 -1.8252201018 +8299 51.6462616706 -1.8198210368 +8300 51.6447103955 -1.8141682202 +8301 51.6434899415 -1.8083097825 +8302 51.6426106944 -1.8022955908 +8303 51.6420801356 -1.796176827 +8304 51.6419027797 -1.7900055556 +8305 51.6420801356 -1.7838342841 +8306 51.6426106944 -1.7777155203 +8307 51.6434899415 -1.7717013286 +8308 51.6447103955 -1.7658428909 +8309 51.6462616706 -1.7601900743 +8310 51.6481305646 -1.7547910093 +8311 51.6503011708 -1.7496916828 +8312 51.6527550116 -1.7449355482 +8313 51.6554711955 -1.7405631563 +8314 51.6584265935 -1.7366118107 +8315 51.6615960349 -1.7331152489 +8316 51.6649525207 -1.7301033542 +8317 51.6684674524 -1.7276018987 +8318 51.6721108749 -1.725632321 +8319 51.6758517307 -1.7242115398 +8320 51.679658124 -1.7233518057 +8321 51.6834975923 -1.7230605927 +8322 51.6873373829 -1.7233405289 +8323 51.691144732 -1.7241893702 +8324 51.6948871446 -1.7256000136 +8325 51.6985326718 -1.7275605536 +8326 51.7020501846 -1.7300543794 +8327 51.7054096398 -1.7330603121 +8328 51.7085823379 -1.7365527828 +8329 51.711541169 -1.7405020475 +8330 51.7142608454 -1.7448744393 +8331 51.7167181193 -1.7496326549 +8332 51.7188919822 -1.7547360725 +8333 51.7207638457 -1.7601410994 +8334 51.7223177018 -1.7658015458 +8335 51.7235402605 -1.7716690211 +8336 51.7244210644 -1.7776933507 +8337 51.7249525789 -1.7838230073 +8338 51.7251302571 -1.7900055556 +8339 51.6769958333 -1.8839879444 +8340 51.6776048333 -1.8562672222 +8341 51.6805888471 -1.85678249 +8342 51.6835881858 -1.8569504954 +8343 51.68658725 -1.8567703056 +8344 51.6859784444 -1.8844827222 +8345 51.6769958333 -1.8839879444 +8346 51.6899902222 -1.6959973611 +8347 51.6894188889 -1.7237330278 +8348 51.686434517 -1.7232232057 +8349 51.683435067 -1.7230607719 +8350 51.6804361389 -1.7232465278 +8351 51.6810076389 -1.6955025278 +8352 51.6899902222 -1.6959973611 +8353 51.2813878265 -1.7548361111 +8354 51.2812112407 -1.7602945509 +8355 51.2806833593 -1.7656950054 +8356 51.2798097898 -1.7709801093 +8357 51.2785998114 -1.7760937305 +8358 51.2770662759 -1.7809815694 +8359 51.2752254703 -1.7855917388 +8360 51.2730969429 -1.7898753167 +8361 51.2707032944 -1.7937868678 +8362 51.268069937 -1.7972849255 +8363 51.2652248232 -1.8003324321 +8364 51.262198148 -1.8028971307 +8365 51.259022027 -1.8049519048 +8366 51.255730155 -1.8064750628 +8367 51.2523574476 -1.8074505644 +8368 51.2489396698 -1.807868186 +8369 51.2455130569 -1.807723624 +8370 51.2421139298 -1.8070185356 +8371 51.2387783101 -1.8057605153 +8372 51.2355415388 -1.80396301 +8373 51.2324379023 -1.8016451713 +8374 51.2295002701 -1.7988316485 +8375 51.2267597475 -1.7955523241 +8376 51.2242453475 -1.7918419943 +8377 51.2219836846 -1.7877399989 +8378 51.2199986946 -1.7832898041 +8379 51.2183113821 -1.7785385418 +8380 51.2169396 -1.7735365123 +8381 51.2158978609 -1.7683366538 +8382 51.2151971852 -1.7629939845 +8383 51.2148449846 -1.7575650239 +8384 51.2148449846 -1.7521071983 +8385 51.2151971852 -1.7466782377 +8386 51.2158978609 -1.7413355684 +8387 51.2169396 -1.7361357099 +8388 51.2183113821 -1.7311336805 +8389 51.2199986946 -1.7263824182 +8390 51.2219836846 -1.7219322233 +8391 51.2242453475 -1.717830228 +8392 51.2267597475 -1.7141198982 +8393 51.2295002701 -1.7108405737 +8394 51.2324379023 -1.7080270509 +8395 51.2355415388 -1.7057092122 +8396 51.2387783101 -1.7039117069 +8397 51.2421139298 -1.7026536866 +8398 51.2455130569 -1.7019485982 +8399 51.2489396698 -1.7018040362 +8400 51.2523574476 -1.7022216578 +8401 51.255730155 -1.7031971595 +8402 51.259022027 -1.7047203175 +8403 51.262198148 -1.7067750915 +8404 51.2652248232 -1.7093397901 +8405 51.268069937 -1.7123872968 +8406 51.2707032944 -1.7158853544 +8407 51.2730969429 -1.7197969055 +8408 51.2752254703 -1.7240804834 +8409 51.2770662759 -1.7286906528 +8410 51.2785998114 -1.7335784917 +8411 51.2798097898 -1.7386921129 +8412 51.2806833593 -1.7439772169 +8413 51.2812112407 -1.7493776714 +8414 51.2813878265 -1.7548361111 +8415 51.2095862778 -1.7974191944 +8416 51.22002175 -1.7833475 +8417 51.2217490699 -1.7872618918 +8418 51.2236908183 -1.7909127083 +8419 51.2258312222 -1.7942702222 +8420 51.2153988056 -1.8083353333 +8421 51.2095862778 -1.7974191944 +8422 51.2883559167 -1.7097918611 +8423 51.2761612222 -1.7262928889 +8424 51.2744320342 -1.7223759775 +8425 51.27248831 -1.7187238237 +8426 51.2703458889 -1.7153661944 +8427 51.2825434722 -1.6988584444 +8428 51.2883559167 -1.7097918611 +8429 51.2596027222 -1.8324731944 +8430 51.25427375 -1.8069665833 +8431 51.2571979427 -1.8058682165 +8432 51.2600480825 -1.8043540669 +8433 51.2628009444 -1.8024363889 +8434 51.2681283889 -1.8279352222 +8435 51.2596027222 -1.8324731944 +8436 51.2365466389 -1.6772466667 +8437 51.2419014167 -1.7027167778 +8438 51.2389779812 -1.7038199435 +8439 51.2361288557 -1.7053382967 +8440 51.2333772222 -1.7072593889 +8441 51.2280209167 -1.6817815278 +8442 51.2365466389 -1.6772466667 +8443 51.194925709 -1.7510111111 +8444 51.1947480177 -1.7571224367 +8445 51.1942164639 -1.7631814827 +8446 51.1933355946 -1.7691364201 +8447 51.1921129447 -1.774936318 +8448 51.1905589717 -1.7805315813 +8449 51.1886869661 -1.7858743789 +8450 51.1865129364 -1.790919054 +8451 51.1840554715 -1.7956225166 +8452 51.1813355807 -1.799944613 +8453 51.178376513 -1.8038484688 +8454 51.1752035572 -1.8073008037 +8455 51.1718438244 -1.8102722147 +8456 51.1683260161 -1.812737425 +8457 51.1646801771 -1.814675497 +8458 51.1609374388 -1.8160700079 +8459 51.1571297523 -1.8169091861 +8460 51.1532896154 -1.8171860069 +8461 51.1494497946 -1.8168982483 +8462 51.1456430459 -1.8160485048 +8463 51.141901835 -1.8146441607 +8464 51.1382580611 -1.8126973227 +8465 51.1347427851 -1.8102247121 +8466 51.1313859657 -1.8072475184 +8467 51.1282162051 -1.8037912153 +8468 51.1252605058 -1.7998853411 +8469 51.1225440417 -1.7955632448 +8470 51.1200899451 -1.7908618005 +8471 51.1179191107 -1.7858210936 +8472 51.1160500185 -1.7804840787 +8473 51.1144985778 -1.7748962157 +8474 51.1132779929 -1.7691050838 +8475 51.112398651 -1.7631599794 +8476 51.111868035 -1.7571114989 +8477 51.1116906599 -1.7510111111 +8478 51.111868035 -1.7449107234 +8479 51.112398651 -1.7388622428 +8480 51.1132779929 -1.7329171384 +8481 51.1144985778 -1.7271260066 +8482 51.1160500185 -1.7215381435 +8483 51.1179191107 -1.7162011287 +8484 51.1200899451 -1.7111604217 +8485 51.1225440417 -1.7064589775 +8486 51.1252605058 -1.7021368811 +8487 51.1282162051 -1.6982310069 +8488 51.1313859657 -1.6947747038 +8489 51.1347427851 -1.6917975101 +8490 51.1382580611 -1.6893248995 +8491 51.141901835 -1.6873780615 +8492 51.1456430459 -1.6859737175 +8493 51.1494497946 -1.6851239739 +8494 51.1532896154 -1.6848362153 +8495 51.1571297523 -1.6851130361 +8496 51.1609374388 -1.6859522143 +8497 51.1646801771 -1.6873467253 +8498 51.1683260161 -1.6892847972 +8499 51.1718438244 -1.6917500075 +8500 51.1752035572 -1.6947214185 +8501 51.178376513 -1.6981737535 +8502 51.1813355807 -1.7020776092 +8503 51.1840554715 -1.7063997056 +8504 51.1865129364 -1.7111031682 +8505 51.1886869661 -1.7161478433 +8506 51.1905589717 -1.7214906409 +8507 51.1921129447 -1.7270859043 +8508 51.1933355946 -1.7328858021 +8509 51.1942164639 -1.7388407396 +8510 51.1947480177 -1.7448997855 +8511 51.194925709 -1.7510111111 +8512 51.1118148056 -1.8188315556 +8513 51.12334375 -1.7969201389 +8514 51.1255025611 -1.8002337125 +8515 51.127805952 -1.8032917451 +8516 51.1302419722 -1.8060783056 +8517 51.1187155278 -1.8279827222 +8518 51.1118148056 -1.8188315556 +8519 51.19420625 -1.6841814444 +8520 51.1832688889 -1.7050659722 +8521 51.1811084272 -1.7017510046 +8522 51.1788033417 -1.6986927047 +8523 51.1763656389 -1.6959069722 +8524 51.1873056111 -1.6750153333 +8525 51.19420625 -1.6841814444 +8526 51.118341 -1.8093775 +8527 51.1241878611 -1.7982730833 +8528 51.1264067992 -1.8014879624 +8529 51.1287657571 -1.8044405247 +8530 51.1312524722 -1.8071153889 +8531 51.1252389167 -1.8185353056 +8532 51.118341 -1.8093775 +8533 51.1872856389 -1.7004613056 +8534 51.1841162222 -1.7065058611 +8535 51.1820178836 -1.7030883915 +8536 51.179770037 -1.6999208758 +8537 51.1773844167 -1.6970197778 +8538 51.1803878056 -1.6912912222 +8539 51.1872856389 -1.7004613056 +8540 51.1098363889 -1.8190288333 +8541 51.12235775 -1.7952359444 +8542 51.1244440448 -1.7986686484 +8543 51.1266806071 -1.8018536395 +8544 51.1290558056 -1.8047743333 +8545 51.1167355 -1.8281826944 +8546 51.1098363889 -1.8190288333 +8547 51.2042225833 -1.7572530278 +8548 51.1948913889 -1.7536991944 +8549 51.1949000253 -1.7486860338 +8550 51.1946701902 -1.7436862295 +8551 51.1942031944 -1.7387285 +8552 51.2063113333 -1.743336 +8553 51.2042225833 -1.7572530278 +8554 51.1021631111 -1.7037857778 +8555 51.1203252222 -1.7106696111 +8556 51.1185007217 -1.7147495861 +8557 51.1168755177 -1.7190368393 +8558 51.1154588889 -1.7235068333 +8559 51.1000743056 -1.7176715 +8560 51.1021631111 -1.7037857778 +8561 51.2445019264 -1.5969805556 +8562 51.2443253397 -1.6024346282 +8563 51.2437974554 -1.6078307621 +8564 51.2429238812 -1.6131116381 +8565 51.2417138962 -1.618221169 +8566 51.2401803523 -1.6231050988 +8567 51.2383395365 -1.6277115819 +8568 51.2362109971 -1.6319917356 +8569 51.2338173351 -1.6359001607 +8570 51.2311839626 -1.6393954239 +8571 51.2283388323 -1.6424404972 +8572 51.2253121392 -1.6450031492 +8573 51.2221359992 -1.6470562849 +8574 51.2188441073 -1.6485782301 +8575 51.215471379 -1.649552957 +8576 51.2120535798 -1.64997025 +8577 51.2086269452 -1.6498258088 +8578 51.2052277961 -1.6491212888 +8579 51.2018921545 -1.6478642784 +8580 51.1986553617 -1.6460682136 +8581 51.1955517043 -1.6437522304 +8582 51.192614052 -1.6409409584 +8583 51.1898735105 -1.637664256 +8584 51.1873590929 -1.6339568916 +8585 51.1850974141 -1.6298581736 +8586 51.1831124099 -1.6254115333 +8587 51.1814250854 -1.6206640652 +8588 51.1800532933 -1.6156660294 +8589 51.1790115467 -1.6104703221 +8590 51.1783108659 -1.6051319175 +8591 51.1779586627 -1.5997072902 +8592 51.1779586627 -1.5942538209 +8593 51.1783108659 -1.5888291937 +8594 51.1790115467 -1.5834907891 +8595 51.1800532933 -1.5782950817 +8596 51.1814250854 -1.573297046 +8597 51.1831124099 -1.5685495778 +8598 51.1850974141 -1.5641029375 +8599 51.1873590929 -1.5600042195 +8600 51.1898735105 -1.5562968551 +8601 51.192614052 -1.5530201527 +8602 51.1955517043 -1.5502088807 +8603 51.1986553617 -1.5478928975 +8604 51.2018921545 -1.5460968327 +8605 51.2052277961 -1.5448398223 +8606 51.2086269452 -1.5441353023 +8607 51.2120535798 -1.5439908611 +8608 51.215471379 -1.5444081541 +8609 51.2188441073 -1.545382881 +8610 51.2221359992 -1.5469048262 +8611 51.2253121392 -1.5489579619 +8612 51.2283388323 -1.5515206139 +8613 51.2311839626 -1.5545656872 +8614 51.2338173351 -1.5580609505 +8615 51.2362109971 -1.5619693756 +8616 51.2383395365 -1.5662495292 +8617 51.2401803523 -1.5708560123 +8618 51.2417138962 -1.5757399421 +8619 51.2429238812 -1.580849473 +8620 51.2437974554 -1.586130349 +8621 51.2443253397 -1.5915264829 +8622 51.2445019264 -1.5969805556 +8623 51.1881222222 -1.6649138889 +8624 51.1941383889 -1.6424814167 +8625 51.1967841337 -1.6447465308 +8626 51.1995473688 -1.6466230757 +8627 51.2024056111 -1.6480957222 +8628 51.1963916667 -1.6705194444 +8629 51.1881222222 -1.6649138889 +8630 51.2342861111 -1.5288583333 +8631 51.22825975 -1.5514453333 +8632 51.2256122627 -1.5491841987 +8633 51.2228475387 -1.5473125872 +8634 51.2199881111 -1.5458456667 +8635 51.2260166667 -1.52325 +8636 51.2342861111 -1.5288583333 +8637 51.2325833333 -1.6677805556 +8638 51.2237947222 -1.6460598611 +8639 51.2265260821 -1.6440514429 +8640 51.2291324058 -1.6416583054 +8641 51.2315923889 -1.6388999444 +8642 51.2401361111 -1.6600138889 +8643 51.2325833333 -1.6677805556 +8644 51.1876861111 -1.5306666667 +8645 51.1956079444 -1.55016125 +8646 51.193017224 -1.5525946413 +8647 51.1905750191 -1.555389954 +8648 51.18830125 -1.5585243611 +8649 51.1801333333 -1.5384222222 +8650 51.1876861111 -1.5306666667 +8651 51.7915992282 -1.5829472222 +8652 51.7914215516 -1.5891388545 +8653 51.790890042 -1.5952775171 +8654 51.7900092462 -1.6013106972 +8655 51.7887866989 -1.6071867917 +8656 51.7872328574 -1.6128555517 +8657 51.7853610116 -1.6182685155 +8658 51.7831871695 -1.6233794253 +8659 51.7807299195 -1.6281446243 +8660 51.7780102697 -1.632523431 +8661 51.7750514682 -1.6364784872 +8662 51.7718788023 -1.6399760768 +8663 51.7685193817 -1.6429864125 +8664 51.7650019058 -1.6454838879 +8665 51.7613564176 -1.6474472935 +8666 51.7576140457 -1.6488599943 +8667 51.7538067388 -1.6497100679 +8668 51.7499669915 -1.6499904014 +8669 51.7461275672 -1.6496987476 +8670 51.7423212184 -1.6488377392 +8671 51.7385804071 -1.6474148615 +8672 51.7349370286 -1.6454423834 +8673 51.7314221399 -1.6429372489 +8674 51.7280656959 -1.6399209283 +8675 51.7248962945 -1.6364192318 +8676 51.7219409343 -1.6324620865 +8677 51.7192247855 -1.6280832799 +8678 51.7167709767 -1.6233201699 +8679 51.7146003992 -1.618213367 +8680 51.7127315299 -1.612806388 +8681 51.7111802756 -1.6071452871 +8682 51.7099598381 -1.6012782652 +8683 51.7090806028 -1.595255262 +8684 51.7085500512 -1.5891275342 +8685 51.7083726977 -1.5829472222 +8686 51.7085500512 -1.5767669102 +8687 51.7090806028 -1.5706391824 +8688 51.7099598381 -1.5646161793 +8689 51.7111802756 -1.5587491573 +8690 51.7127315299 -1.5530880564 +8691 51.7146003992 -1.5476810775 +8692 51.7167709767 -1.5425742745 +8693 51.7192247855 -1.5378111646 +8694 51.7219409343 -1.5334323579 +8695 51.7248962945 -1.5294752127 +8696 51.7280656959 -1.5259735161 +8697 51.7314221399 -1.5229571956 +8698 51.7349370286 -1.5204520611 +8699 51.7385804071 -1.518479583 +8700 51.7423212184 -1.5170567052 +8701 51.7461275672 -1.5161956968 +8702 51.7499669915 -1.515904043 +8703 51.7538067388 -1.5161843765 +8704 51.7576140457 -1.5170344501 +8705 51.7613564176 -1.518447151 +8706 51.7650019058 -1.5204105566 +8707 51.7685193817 -1.522908032 +8708 51.7718788023 -1.5259183676 +8709 51.7750514682 -1.5294159573 +8710 51.7780102697 -1.5333710135 +8711 51.7807299195 -1.5377498201 +8712 51.7831871695 -1.5425150191 +8713 51.7853610116 -1.5476259289 +8714 51.7872328574 -1.5530388928 +8715 51.7887866989 -1.5587076528 +8716 51.7900092462 -1.5645837472 +8717 51.790890042 -1.5706169273 +8718 51.7914215516 -1.5767555899 +8719 51.7915992282 -1.5829472222 +8720 51.72900125 -1.6714538333 +8721 51.7339242778 -1.6447841389 +8722 51.736732361 -1.6464897503 +8723 51.7396094469 -1.6478651552 +8724 51.7425405833 -1.6489031389 +8725 51.7376190556 -1.6755641667 +8726 51.72900125 -1.6714538333 +8727 51.7709242778 -1.4943830556 +8728 51.7660371944 -1.5210811389 +8729 51.7632279118 -1.5193796402 +8730 51.7603498265 -1.5180090481 +8731 51.7574179167 -1.5169764444 +8732 51.7623065278 -1.4902697222 +8733 51.7709242778 -1.4943830556 +8734 51.1742773282 -1.5726722222 +8735 51.1741007397 -1.5781180062 +8736 51.17357285 -1.5835059398 +8737 51.1726992668 -1.5887787912 +8738 51.1714892692 -1.5938805588 +8739 51.1699557093 -1.5987570692 +8740 51.168114874 -1.6033565558 +8741 51.165986312 -1.6076302102 +8742 51.1635926242 -1.6115327024 +8743 51.1609592229 -1.6150226618 +8744 51.1581140612 -1.6180631166 +8745 51.1550873341 -1.6206218842 +8746 51.1519111579 -1.6226719104 +8747 51.1486192279 -1.6241915537 +8748 51.14524646 -1.6251648102 +8749 51.1418286201 -1.6255814795 +8750 51.1384019438 -1.6254372673 +8751 51.135002753 -1.6247338262 +8752 51.1316670697 -1.6234787327 +8753 51.1284302359 -1.6216854019 +8754 51.1253265386 -1.6193729405 +8755 51.1223888482 -1.6165659404 +8756 51.1196482706 -1.6132942145 +8757 51.1171338196 -1.6095924784 +8758 51.1148721104 -1.6054999807 +8759 51.1128870793 -1.6010600869 +8760 51.1111997318 -1.59631982 +8761 51.1098279209 -1.5913293643 +8762 51.10878616 -1.5861415357 +8763 51.1080854694 -1.5808112254 +8764 51.1077332614 -1.5753948227 +8765 51.1077332614 -1.5699496217 +8766 51.1080854694 -1.564533219 +8767 51.10878616 -1.5592029088 +8768 51.1098279209 -1.5540150801 +8769 51.1111997318 -1.5490246244 +8770 51.1128870793 -1.5442843576 +8771 51.1148721104 -1.5398444637 +8772 51.1171338196 -1.535751966 +8773 51.1196482706 -1.5320502299 +8774 51.1223888482 -1.5287785041 +8775 51.1253265386 -1.525971504 +8776 51.1284302359 -1.5236590426 +8777 51.1316670697 -1.5218657117 +8778 51.135002753 -1.5206106182 +8779 51.1384019438 -1.5199071771 +8780 51.1418286201 -1.5197629649 +8781 51.14524646 -1.5201796342 +8782 51.1486192279 -1.5211528908 +8783 51.1519111579 -1.522672534 +8784 51.1550873341 -1.5247225603 +8785 51.1581140612 -1.5272813278 +8786 51.1609592229 -1.5303217826 +8787 51.1635926242 -1.5338117421 +8788 51.165986312 -1.5377142342 +8789 51.168114874 -1.5419878886 +8790 51.1699557093 -1.5465873752 +8791 51.1714892692 -1.5514638856 +8792 51.1726992668 -1.5565656532 +8793 51.17357285 -1.5618385047 +8794 51.1741007397 -1.5672264383 +8795 51.1742773282 -1.5726722222 +8796 51.1365355833 -1.6450034167 +8797 51.13786925 -1.6253642222 +8798 51.140904555 -1.6255978757 +8799 51.1439406175 -1.6253905593 +8800 51.1469521389 -1.6247439722 +8801 51.14547325 -1.6465238611 +8802 51.1365355833 -1.6450034167 +8803 51.15600175 -1.4901112778 +8804 51.153753 -1.52378725 +8805 51.1508959449 -1.5221410871 +8806 51.1479563643 -1.5209162238 +8807 51.1449587778 -1.5201227222 +8808 51.1470641111 -1.4885904722 +8809 51.15600175 -1.4901112778 +8810 51.1903857222 -1.588953 +8811 51.1732382222 -1.5857961667 +8812 51.1738510424 -1.5811173714 +8813 51.1741960353 -1.5763696609 +8814 51.1742703889 -1.5715917778 +8815 51.1914171111 -1.5747432222 +8816 51.1903857222 -1.588953 +8817 51.0915795 -1.556427 +8818 51.1087266944 -1.5595671111 +8819 51.1081147689 -1.5642396379 +8820 51.1077702969 -1.5689806823 +8821 51.1076960833 -1.5737517222 +8822 51.0905481111 -1.5706061667 +8823 51.0915795 -1.556427 +8824 51.8702344667 -1.32 +8825 51.870057896 -1.3255294318 +8826 51.8695300599 -1.3310001216 +8827 51.8686565655 -1.3363539553 +8828 51.8674466918 -1.3415340685 +8829 51.86591329 -1.3464854536 +8830 51.8640726463 -1.351155547 +8831 51.861944308 -1.3554947899 +8832 51.8595508747 -1.3594571558 +8833 51.8569177572 -1.3630006394 +8834 51.8540729061 -1.3660877023 +8835 51.8510465145 -1.3686856699 +8836 51.8478706957 -1.3707670754 +8837 51.8445791419 -1.3723099481 +8838 51.8412067656 -1.3732980424 +8839 51.8377893287 -1.3737210051 +8840 51.8343630631 -1.3735744804 +8841 51.8309642858 -1.3728601504 +8842 51.8276290146 -1.371585712 +8843 51.8243925863 -1.3697647898 +8844 51.8212892834 -1.3674167871 +8845 51.8183519709 -1.3645666756 +8846 51.8156117502 -1.3612447278 +8847 51.8130976302 -1.3574861927 +8848 51.8108362217 -1.3533309217 +8849 51.8088514569 -1.3488229448 +8850 51.8071643374 -1.3440100053 +8851 51.805792713 -1.3389430551 +8852 51.8047510943 -1.3336757173 +8853 51.8040504998 -1.3282637222 +8854 51.8036983402 -1.3227643201 +8855 51.8036983402 -1.3172356799 +8856 51.8040504998 -1.3117362778 +8857 51.8047510943 -1.3063242827 +8858 51.805792713 -1.3010569449 +8859 51.8071643374 -1.2959899947 +8860 51.8088514569 -1.2911770552 +8861 51.8108362217 -1.2866690783 +8862 51.8130976302 -1.2825138073 +8863 51.8156117502 -1.2787552722 +8864 51.8183519709 -1.2754333244 +8865 51.8212892834 -1.2725832129 +8866 51.8243925863 -1.2702352102 +8867 51.8276290146 -1.268414288 +8868 51.8309642858 -1.2671398496 +8869 51.8343630631 -1.2664255196 +8870 51.8377893287 -1.2662789949 +8871 51.8412067656 -1.2667019576 +8872 51.8445791419 -1.2676900519 +8873 51.8478706957 -1.2692329246 +8874 51.8510465145 -1.2713143301 +8875 51.8540729061 -1.2739122977 +8876 51.8569177572 -1.2769993606 +8877 51.8595508747 -1.2805428442 +8878 51.861944308 -1.2845052101 +8879 51.8640726463 -1.288844453 +8880 51.86591329 -1.2935145464 +8881 51.8674466918 -1.2984659315 +8882 51.8686565655 -1.3036460447 +8883 51.8695300599 -1.3089998784 +8884 51.870057896 -1.3144705682 +8885 51.8702344667 -1.32 +8886 51.7861444444 -1.3280333333 +8887 51.80369625 -1.3226977778 +8888 51.8039822011 -1.3275216808 +8889 51.8045363966 -1.3322844625 +8890 51.8053543333 -1.3369474167 +8891 51.7878111111 -1.342275 +8892 51.7861444444 -1.3280333333 +8893 51.8877833333 -1.3118583333 +8894 51.8701899722 -1.3172211389 +8895 51.8698993105 -1.3123911033 +8896 51.8693401192 -1.3076231617 +8897 51.8685169444 -1.3029562222 +8898 51.8861166667 -1.2975861111 +8899 51.8877833333 -1.3118583333 +8900 51.6483301753 -1.0958472222 +8901 51.648153599 -1.1013496162 +8902 51.6476257459 -1.1067935565 +8903 51.6467522233 -1.112121214 +8904 51.6455423103 -1.1172760033 +8905 51.6440088582 -1.1222031865 +8906 51.6421681537 -1.1268504575 +8907 51.6400397443 -1.1311685001 +8908 51.6376462301 -1.1351115129 +8909 51.6350130224 -1.1386376959 +8910 51.6321680726 -1.1417096938 +8911 51.6291415743 -1.1442949908 +8912 51.6259656419 -1.1463662537 +8913 51.6226739684 -1.1479016182 +8914 51.6193014675 -1.1488849166 +8915 51.6158839024 -1.1493058453 +8916 51.6124575061 -1.1491600683 +8917 51.6090585972 -1.1484492582 +8918 51.6057231948 -1.1471810729 +8919 51.6024866374 -1.1453690692 +8920 51.5993832088 -1.1430325547 +8921 51.596445776 -1.1401963783 +8922 51.5937054416 -1.1368906638 +8923 51.5911912162 -1.1331504879 +8924 51.5889297119 -1.1290155071 +8925 51.5869448622 -1.1245295367 +8926 51.58525767 -1.1197400871 +8927 51.5838859862 -1.1146978621 +8928 51.5828443222 -1.109456224 +8929 51.5821436971 -1.1040706317 +8930 51.581791522 -1.0985980574 +8931 51.581791522 -1.0930963871 +8932 51.5821436971 -1.0876238127 +8933 51.5828443222 -1.0822382205 +8934 51.5838859862 -1.0769965823 +8935 51.58525767 -1.0719543573 +8936 51.5869448622 -1.0671649077 +8937 51.5889297119 -1.0626789373 +8938 51.5911912162 -1.0585439565 +8939 51.5937054416 -1.0548037807 +8940 51.596445776 -1.0514980662 +8941 51.5993832088 -1.0486618898 +8942 51.6024866374 -1.0463253752 +8943 51.6057231948 -1.0445133716 +8944 51.6090585972 -1.0432451862 +8945 51.6124575061 -1.0425343761 +8946 51.6158839024 -1.0423885991 +8947 51.6193014675 -1.0428095278 +8948 51.6226739684 -1.0437928263 +8949 51.6259656419 -1.0453281907 +8950 51.6291415743 -1.0473994536 +8951 51.6321680726 -1.0499847507 +8952 51.6350130224 -1.0530567485 +8953 51.6376462301 -1.0565829315 +8954 51.6400397443 -1.0605259443 +8955 51.6421681537 -1.064843987 +8956 51.6440088582 -1.069491258 +8957 51.6455423103 -1.0744184411 +8958 51.6467522233 -1.0795732304 +8959 51.6476257459 -1.084900888 +8960 51.648153599 -1.0903448282 +8961 51.6483301753 -1.0958472222 +8962 51.5617916667 -1.1003111111 +8963 51.5817474444 -1.0959105556 +8964 51.5818864152 -1.100727273 +8965 51.5822951597 -1.1055043408 +8966 51.5829703333 -1.1102029444 +8967 51.5630138889 -1.1145972222 +8968 51.5617916667 -1.1003111111 +8969 51.6682888889 -1.0913722222 +8970 51.6483301389 -1.09578375 +8971 51.6481909345 -1.0909598326 +8972 51.6477815696 -1.0861758008 +8973 51.6471053889 -1.0814706944 +8974 51.6670638889 -1.0770527778 +8975 51.6682888889 -1.0913722222 +8976 51.7078020585 -1.08525 +8977 51.7076254837 -1.0907596062 +8978 51.7070976351 -1.0962106817 +8979 51.7062241201 -1.1015453216 +8980 51.7050142177 -1.1067068659 +8981 51.7034807791 -1.1116405047 +8982 51.7016400909 -1.1162938635 +8983 51.6995117006 -1.1206175612 +8984 51.6971182081 -1.1245657363 +8985 51.6944850246 -1.1280965342 +8986 51.6916401013 -1.1311725506 +8987 51.6886136316 -1.1337612274 +8988 51.6854377297 -1.1358351958 +8989 51.6821460883 -1.1373725631 +8990 51.6787736208 -1.1383571408 +8991 51.6753560901 -1.1387786121 +8992 51.6719297288 -1.1386326357 +8993 51.6685308552 -1.1379208867 +8994 51.665195488 -1.1366510334 +8995 51.6619589652 -1.1348366508 +8996 51.6588555703 -1.1324970718 +8997 51.6559181698 -1.1296571783 +8998 51.6531778659 -1.1263471336 +8999 51.6506636687 -1.1226020606 +9000 51.6484021901 -1.1184616675 +9001 51.6464173632 -1.113969827 +9002 51.6447301904 -1.1091741116 +9003 51.6433585225 -1.1041252912 +9004 51.6423168707 -1.0988767978 +9005 51.6416162538 -1.0934841627 +9006 51.6412640828 -1.0880044322 +9007 51.6412640828 -1.0824955678 +9008 51.6416162538 -1.0770158373 +9009 51.6423168707 -1.0716232022 +9010 51.6433585225 -1.0663747088 +9011 51.6447301904 -1.0613258884 +9012 51.6464173632 -1.056530173 +9013 51.6484021901 -1.0520383325 +9014 51.6506636687 -1.0478979394 +9015 51.6531778659 -1.0441528664 +9016 51.6559181698 -1.0408428217 +9017 51.6588555703 -1.0380029282 +9018 51.6619589652 -1.0356633492 +9019 51.665195488 -1.0338489666 +9020 51.6685308552 -1.0325791133 +9021 51.6719297288 -1.0318673643 +9022 51.6753560901 -1.0317213879 +9023 51.6787736208 -1.0321428592 +9024 51.6821460883 -1.0331274369 +9025 51.6854377297 -1.0346648042 +9026 51.6886136316 -1.0367387726 +9027 51.6916401013 -1.0393274494 +9028 51.6944850246 -1.0424034658 +9029 51.6971182081 -1.0459342637 +9030 51.6995117006 -1.0498824388 +9031 51.7016400909 -1.0542061365 +9032 51.7034807791 -1.0588594953 +9033 51.7050142177 -1.0637931341 +9034 51.7062241201 -1.0689546784 +9035 51.7070976351 -1.0742893183 +9036 51.7076254837 -1.0797403938 +9037 51.7078020585 -1.08525 +9038 51.2674851282 -0.9428083333 +9039 51.2673085421 -0.948265126 +9040 51.2667806596 -0.9536639509 +9041 51.2659070883 -0.9589474603 +9042 51.2646971075 -0.9640595388 +9043 51.2631635688 -0.9689459033 +9044 51.2613227593 -0.9735546824 +9045 51.2591942274 -0.9778369688 +9046 51.2568005738 -0.9817473409 +9047 51.2541672107 -0.9852443446 +9048 51.2513220907 -0.9882909335 +9049 51.2482954088 -0.9908548602 +9050 51.2451192806 -0.9929090163 +9051 51.2418274011 -0.9944317169 +9052 51.2384546858 -0.9954069263 +9053 51.2350369 -0.995824424 +9054 51.2316102789 -0.9956799076 +9055 51.2282111435 -0.9949750335 +9056 51.2248755156 -0.9937173942 +9057 51.2216387361 -0.9919204321 +9058 51.2185350918 -0.9896032933 +9059 51.215597452 -0.9867906194 +9060 51.2128569223 -0.9835122839 +9061 51.2103425156 -0.9798030725 +9062 51.2080808467 -0.9757023133 +9063 51.2060958514 -0.971253459 +9064 51.2044085344 -0.9665036277 +9065 51.2030367485 -0.9615031045 +9066 51.2019950066 -0.9563048117 +9067 51.2012943289 -0.9509637509 +9068 51.2009421274 -0.9455364246 +9069 51.2009421274 -0.9400802421 +9070 51.2012943289 -0.9346529158 +9071 51.2019950066 -0.929311855 +9072 51.2030367485 -0.9241135621 +9073 51.2044085344 -0.919113039 +9074 51.2060958514 -0.9143632076 +9075 51.2080808467 -0.9099143534 +9076 51.2103425156 -0.9058135942 +9077 51.2128569223 -0.9021043828 +9078 51.215597452 -0.8988260473 +9079 51.2185350918 -0.8960133734 +9080 51.2216387361 -0.8936962345 +9081 51.2248755156 -0.8918992725 +9082 51.2282111435 -0.8906416331 +9083 51.2316102789 -0.8899367591 +9084 51.2350369 -0.8897922427 +9085 51.2384546858 -0.8902097403 +9086 51.2418274011 -0.8911849498 +9087 51.2451192806 -0.8927076503 +9088 51.2482954088 -0.8947618065 +9089 51.2513220907 -0.8973257332 +9090 51.2541672107 -0.9003723221 +9091 51.2568005738 -0.9038693258 +9092 51.2591942274 -0.9077796979 +9093 51.2613227593 -0.9120619843 +9094 51.2631635688 -0.9166707633 +9095 51.2646971075 -0.9215571279 +9096 51.2659070883 -0.9266692064 +9097 51.2667806596 -0.9319527157 +9098 51.2673085421 -0.9373515407 +9099 51.2674851282 -0.9428083333 +9100 51.2320944444 -1.0277194444 +9101 51.2311932778 -0.9956238056 +9102 51.2341948201 -0.9958410278 +9103 51.2371964328 -0.9956263241 +9104 51.2401736667 -0.9949813611 +9105 51.241075 -1.0270638889 +9106 51.2320944444 -1.0277194444 +9107 51.2362194444 -0.8577777778 +9108 51.2371621944 -0.8899854444 +9109 51.2341610401 -0.889775671 +9110 51.2311602307 -0.8899976551 +9111 51.2281841944 -0.8906495 +9112 51.2272416667 -0.8584305556 +9113 51.2362194444 -0.8577777778 +9114 51.2939527778 -0.87075 +9115 51.2962277778 -0.8556861111 +9116 51.29795 -0.8438138889 +9117 51.2993666667 -0.8316222222 +9118 51.3003611111 -0.8219555556 +9119 51.3015972222 -0.8080277778 +9120 51.3042314235 -0.8046211679 +9121 51.3070659151 -0.8016523744 +9122 51.3100749158 -0.7991585751 +9123 51.3132272484 -0.7971657046 +9124 51.3164902437 -0.7956945204 +9125 51.319830079 -0.7947603842 +9126 51.3232121275 -0.7943730988 +9127 51.3266013175 -0.7945368009 +9128 51.3299624951 -0.7952499138 +9129 51.3332607896 -0.7965051585 +9130 51.3364619755 -0.7982896245 +9131 51.3395328276 -0.8005848991 +9132 51.3424414674 -0.8033672544 +9133 51.3451576942 -0.8066078902 +9134 51.3476533001 -0.8102732304 +9135 51.349902364 -0.8143252696 +9136 51.3518815221 -0.8187219672 +9137 51.3535702113 -0.8234176835 +9138 51.3549508846 -0.8283636551 +9139 51.3560091942 -0.833508503 +9140 51.3567341412 -0.838798769 +9141 51.3571181909 -0.8441794738 +9142 51.3571573517 -0.8495946925 +9143 51.3568512164 -0.8549881386 +9144 51.3562029671 -0.860303754 +9145 51.3552193412 -0.8654862942 +9146 51.3539105616 -0.8704819069 +9147 51.3522902294 -0.875238694 +9148 51.3503751817 -0.879707254 +9149 51.3481853158 -0.8838411967 +9150 51.3457433816 -0.8875976263 +9151 51.3430747435 -0.8909375871 +9152 51.3402071163 -0.8938264674 +9153 51.337170276 -0.8962343572 +9154 51.3339957498 -0.8981363562 +9155 51.3307164872 -0.8995128292 +9156 51.3273665183 -0.9003496056 +9157 51.3239805991 -0.9006381222 +9158 51.3205938511 -0.9003755074 +9159 51.3172413967 -0.8995646057 +9160 51.3139579952 -0.8982139433 +9161 51.3107776825 -0.8963376347 +9162 51.307733419 -0.8939552325 +9163 51.3048567489 -0.8910915201 +9164 51.3021774742 -0.887776252 +9165 51.2997233468 -0.8840438431 +9166 51.2975197822 -0.8799330102 +9167 51.2955895979 -0.8754863704 +9168 51.2939527778 -0.87075 +9169 51.3040638889 -0.9204 +9170 51.3093216389 -0.8952721667 +9171 51.3120790247 -0.8971743106 +9172 51.3149326267 -0.8986723185 +9173 51.3178592222 -0.8997539444 +9174 51.3125916667 -0.9249277778 +9175 51.3040638889 -0.9204 +9176 51.343825 -0.7751972222 +9177 51.3386891667 -0.7998953611 +9178 51.3359402315 -0.7979607589 +9179 51.3330932315 -0.7964298273 +9180 51.3301713611 -0.7953149722 +9181 51.3352972222 -0.7706638889 +9182 51.343825 -0.7751972222 +9183 51.6450218609 -0.8082305556 +9184 51.6448452845 -0.8137325491 +9185 51.6443174311 -0.8191760931 +9186 51.6434439081 -0.824503363 +9187 51.6422339944 -0.8296577772 +9188 51.6407005416 -0.8345846019 +9189 51.6388598362 -0.8392315348 +9190 51.6367314258 -0.8435492635 +9191 51.6343379104 -0.8474919896 +9192 51.6317047013 -0.8510179164 +9193 51.62885975 -0.8540896911 +9194 51.6258332502 -0.8566748005 +9195 51.622657316 -0.8587459132 +9196 51.6193656408 -0.8602811664 +9197 51.615993138 -0.8612643938 +9198 51.612575571 -0.8616852924 +9199 51.6091491728 -0.8615395265 +9200 51.6057502619 -0.8608287685 +9201 51.6024148575 -0.8595606757 +9202 51.5991782982 -0.8577488042 +9203 51.5960748678 -0.8554124598 +9204 51.5931374331 -0.8525764898 +9205 51.590397097 -0.8492710157 +9206 51.58788287 -0.8455311118 +9207 51.5856213643 -0.8413964315 +9208 51.5836365134 -0.8369107871 +9209 51.5819493201 -0.8321216854 +9210 51.5805776354 -0.8270798266 +9211 51.5795359707 -0.8218385692 +9212 51.5788353451 -0.816453368 +9213 51.5784831698 -0.810981191 +9214 51.5784831698 -0.8054799201 +9215 51.5788353451 -0.8000077431 +9216 51.5795359707 -0.794622542 +9217 51.5805776354 -0.7893812845 +9218 51.5819493201 -0.7843394257 +9219 51.5836365134 -0.779550324 +9220 51.5856213643 -0.7750646796 +9221 51.58788287 -0.7709299993 +9222 51.590397097 -0.7671900954 +9223 51.5931374331 -0.7638846213 +9224 51.5960748678 -0.7610486513 +9225 51.5991782982 -0.7587123069 +9226 51.6024148575 -0.7569004354 +9227 51.6057502619 -0.7556323426 +9228 51.6091491728 -0.7549215847 +9229 51.612575571 -0.7547758187 +9230 51.615993138 -0.7551967173 +9231 51.6193656408 -0.7561799447 +9232 51.622657316 -0.757715198 +9233 51.6258332502 -0.7597863106 +9234 51.62885975 -0.76237142 +9235 51.6317047013 -0.7654431947 +9236 51.6343379104 -0.7689691215 +9237 51.6367314258 -0.7729118476 +9238 51.6388598362 -0.7772295763 +9239 51.6407005416 -0.7818765093 +9240 51.6422339944 -0.7868033339 +9241 51.6434439081 -0.7919577481 +9242 51.6443174311 -0.797285018 +9243 51.6448452845 -0.802728562 +9244 51.6450218609 -0.8082305556 +9245 51.5854194444 -0.8734888889 +9246 51.5924746389 -0.8518406944 +9247 51.5950007053 -0.8544514271 +9248 51.597663026 -0.8566861956 +9249 51.6004399444 -0.85852675 +9250 51.5933861111 -0.8801694444 +9251 51.5854194444 -0.8734888889 +9252 51.6380305556 -0.7428694444 +9253 51.6309821389 -0.7645970833 +9254 51.6284546928 -0.7619873992 +9255 51.6257910769 -0.7597547123 +9256 51.623013 -0.7579171667 +9257 51.6300638889 -0.7361805556 +9258 51.6380305556 -0.7428694444 +9259 51.5851333333 -0.8717527778 +9260 51.591854 -0.8511163333 +9261 51.5943427601 -0.8538205929 +9262 51.5969732224 -0.8561537856 +9263 51.5997239722 -0.8580968611 +9264 51.5931027778 -0.8784277778 +9265 51.5851333333 -0.8717527778 +9266 51.6373111111 -0.7423638889 +9267 51.6303364444 -0.7638803889 +9268 51.627771051 -0.7613668981 +9269 51.6250750191 -0.7592355649 +9270 51.6222703333 -0.7575036944 +9271 51.6293444444 -0.7356805556 +9272 51.6373111111 -0.7423638889 +9273 51.5641660833 -0.7843015278 +9274 51.5804449444 -0.7899565833 +9275 51.5795466346 -0.7945577486 +9276 51.5789101889 -0.7992699984 +9277 51.5785408056 -0.8040550556 +9278 51.562262 -0.798395 +9279 51.5641660833 -0.7843015278 +9280 51.2993666667 -0.8316222222 +9281 51.2961419297 -0.8349233581 +9282 51.2927409314 -0.8377383331 +9283 51.2891919749 -0.8400421019 +9284 51.2855251742 -0.8418152365 +9285 51.2817716363 -0.8430428226 +9286 51.2779631961 -0.843714583 +9287 51.2741321464 -0.8438249598 +9288 51.2703109638 -0.8433731571 +9289 51.2665320331 -0.842363143 +9290 51.2628273734 -0.8408036111 +9291 51.2592283667 -0.8387079028 +9292 51.2557654929 -0.8360938895 +9293 51.2524680725 -0.8329838181 +9294 51.2493640189 -0.829404119 +9295 51.2464796031 -0.8253851801 +9296 51.2438392327 -0.8209610875 +9297 51.2414652461 -0.8161693361 +9298 51.2393777248 -0.8110505121 +9299 51.2375943248 -0.8056479499 +9300 51.2361301276 -0.8000073667 +9301 51.2349975143 -0.7941764778 +9302 51.2342060613 -0.7882045952 +9303 51.23376246 -0.7821422136 +9304 51.2336704608 -0.776040587 +9305 51.2339308414 -0.7699512981 +9306 51.2345414005 -0.7639258263 +9307 51.2354969763 -0.758015116 +9308 51.2367894894 -0.7522691488 +9309 51.238408011 -0.7467365243 +9310 51.2403388547 -0.7414640515 +9311 51.2425656908 -0.7364963554 +9312 51.2450696839 -0.7318755007 +9313 51.2478296513 -0.7276406369 +9314 51.2508222408 -0.7238276671 +9315 51.2540221271 -0.7204689437 +9316 51.2574022255 -0.7175929929 +9317 51.2609339197 -0.7152242709 +9318 51.2645873035 -0.7133829545 +9319 51.2683314329 -0.7120847664 +9320 51.2721345878 -0.7113408381 +9321 51.2759645403 -0.7111576111 +9322 51.2797888272 -0.7115367784 +9323 51.2835750257 -0.7124752644 +9324 51.2872910278 -0.7139652472 +9325 51.290905313 -0.7159942199 +9326 51.2943872168 -0.7185450924 +9327 51.2977071907 -0.7215963329 +9328 51.3008370544 -0.725122147 +9329 51.3037502357 -0.729092694 +9330 51.3064219971 -0.7334743386 +9331 51.3088296472 -0.7382299347 +9332 51.3109527342 -0.7433191407 +9333 51.3127732211 -0.7486987626 +9334 51.3142756395 -0.7543231217 +9335 51.3154472222 -0.7601444444 +9336 51.3140444444 -0.7641027778 +9337 51.3046388889 -0.7846027778 +9338 51.3033833333 -0.7897027778 +9339 51.3015972222 -0.8080277778 +9340 51.3003611111 -0.8219555556 +9341 51.2993666667 -0.8316222222 +9342 51.2477583333 -0.8450972222 +9343 51.2519783056 -0.8324629167 +9344 51.2545235792 -0.8349976079 +9345 51.2571768339 -0.8372336199 +9346 51.2599242778 -0.8391593056 +9347 51.2556972222 -0.8518138889 +9348 51.2477583333 -0.8450972222 +9349 51.3031861111 -0.709275 +9350 51.2987325 -0.7226773611 +9351 51.2961928717 -0.7201248589 +9352 51.2935444601 -0.717871246 +9353 51.2908010556 -0.7159282222 +9354 51.2952472222 -0.7025472222 +9355 51.3031861111 -0.709275 +9356 51.5339502723 -0.7748333333 +9357 51.5337736931 -0.7803219262 +9358 51.5332458312 -0.7857522123 +9359 51.532372294 -0.7910665085 +9360 51.5311623606 -0.7962083715 +9361 51.5296288826 -0.801123201 +9362 51.5277881466 -0.8057588225 +9363 51.5256597005 -0.8100660436 +9364 51.5232661445 -0.8139991778 +9365 51.5206328903 -0.8175165298 +9366 51.5177878894 -0.8205808377 +9367 51.5147613361 -0.8231596671 +9368 51.5115853449 -0.8252257528 +9369 51.5082936097 -0.8267572846 +9370 51.5049210445 -0.827738135 +9371 51.5015034131 -0.8281580254 +9372 51.4980769494 -0.8280126299 +9373 51.4946779725 -0.8273036164 +9374 51.4913425024 -0.8260386228 +9375 51.4881058784 -0.8242311716 +9376 51.4850023851 -0.821900521 +9377 51.4820648901 -0.8190714576 +9378 51.4793244971 -0.8157740293 +9379 51.4768102173 -0.8120432247 +9380 51.4745486636 -0.807918601 +9381 51.4725637701 -0.8034438637 +9382 51.4708765405 -0.7986664044 +9383 51.469504826 -0.7936368003 +9384 51.4684631386 -0.7884082804 +9385 51.4677624977 -0.7830361654 +9386 51.4674103147 -0.7775772851 +9387 51.4674103147 -0.7720893815 +9388 51.4677624977 -0.7666305013 +9389 51.4684631386 -0.7612583863 +9390 51.469504826 -0.7560298664 +9391 51.4708765405 -0.7510002623 +9392 51.4725637701 -0.746222803 +9393 51.4745486636 -0.7417480657 +9394 51.4768102173 -0.7376234419 +9395 51.4793244971 -0.7338926374 +9396 51.4820648901 -0.7305952091 +9397 51.4850023851 -0.7277661456 +9398 51.4881058784 -0.7254354951 +9399 51.4913425024 -0.7236280438 +9400 51.4946779725 -0.7223630502 +9401 51.4980769494 -0.7216540367 +9402 51.5015034131 -0.7215086413 +9403 51.5049210445 -0.7219285317 +9404 51.5082936097 -0.7229093821 +9405 51.5115853449 -0.7244409139 +9406 51.5147613361 -0.7265069995 +9407 51.5177878894 -0.729085829 +9408 51.5206328903 -0.7321501369 +9409 51.5232661445 -0.7356674889 +9410 51.5256597005 -0.7396006231 +9411 51.5277881466 -0.7439078442 +9412 51.5296288826 -0.7485434657 +9413 51.5311623606 -0.7534582952 +9414 51.532372294 -0.7586001581 +9415 51.5332458312 -0.7639144543 +9416 51.5337736931 -0.7693447405 +9417 51.5339502723 -0.7748333333 +9418 51.4534388889 -0.8004888889 +9419 51.4684981389 -0.7886194722 +9420 51.4694066717 -0.7932141707 +9421 51.4705705112 -0.7976589203 +9422 51.4719801667 -0.8019174444 +9423 51.4574138889 -0.8133944444 +9424 51.4534388889 -0.8004888889 +9425 51.5463361111 -0.7432027778 +9426 51.5315407778 -0.7549029444 +9427 51.5302910944 -0.7505130261 +9428 51.5287990749 -0.746322272 +9429 51.5270769444 -0.7423649722 +9430 51.5423638889 -0.7302722222 +9431 51.5463361111 -0.7432027778 +9432 51.4752861111 -0.8435944444 +9433 51.482447 -0.8194776389 +9434 51.4850334633 -0.8219270335 +9435 51.4877472443 -0.8239931833 +9436 51.49056625 -0.8256592222 +9437 51.4834083333 -0.8497666667 +9438 51.4752861111 -0.8435944444 +9439 51.5259861111 -0.7060083333 +9440 51.51885275 -0.7301535556 +9441 51.5162648704 -0.7277079881 +9442 51.5135499515 -0.7256465231 +9443 51.5107301111 -0.7239859167 +9444 51.5178666667 -0.6998305556 +9445 51.5259861111 -0.7060083333 +9446 51.5107083333 -0.8499277778 +9447 51.5056710833 -0.8275695 +9448 51.5086235565 -0.8266300624 +9449 51.5115109942 -0.8252669632 +9450 51.5143097778 -0.8234912778 +9451 51.5191611111 -0.8450222222 +9452 51.5107083333 -0.8499277778 +9453 51.4859083333 -0.6978833333 +9454 51.4917057222 -0.7234618056 +9455 51.4888470135 -0.724968234 +9456 51.4860848759 -0.7268817969 +9457 51.4834418611 -0.7291868056 +9458 51.4774583333 -0.7027833333 +9459 51.4859083333 -0.6978833333 +9460 51.8255736098 -0.73645 +9461 51.825397038 -0.7419739621 +9462 51.8248691985 -0.7474392404 +9463 51.8239956984 -0.7527877787 +9464 51.8227858168 -0.7579627689 +9465 51.8212524049 -0.7629092579 +9466 51.819411749 -0.7675747343 +9467 51.8172833964 -0.7719096885 +9468 51.8148899469 -0.7758681392 +9469 51.8122568112 -0.7794081229 +9470 51.8094119403 -0.7824921382 +9471 51.8063855272 -0.7850875426 +9472 51.8032096856 -0.7871668962 +9473 51.7999181077 -0.78870825 +9474 51.7965457063 -0.7896953741 +9475 51.7931282437 -0.7901179254 +9476 51.7897019518 -0.789971552 +9477 51.786303148 -0.7892579341 +9478 51.7829678504 -0.7879847607 +9479 51.7797313962 -0.7861656427 +9480 51.7766280679 -0.7838199641 +9481 51.7736907313 -0.7809726717 +9482 51.7709504877 -0.7776540078 +9483 51.7684363465 -0.7738991868 +9484 51.7661749187 -0.7697480205 +9485 51.7641901369 -0.7652444955 +9486 51.7625030027 -0.760436308 +9487 51.7611313664 -0.7553743596 +9488 51.7600897386 -0.7501122209 +9489 51.7593891379 -0.744705567 +9490 51.7590369751 -0.7392115921 +9491 51.7590369751 -0.7336884079 +9492 51.7593891379 -0.728194433 +9493 51.7600897386 -0.7227877791 +9494 51.7611313664 -0.7175256404 +9495 51.7625030027 -0.712463692 +9496 51.7641901369 -0.7076555045 +9497 51.7661749187 -0.7031519795 +9498 51.7684363465 -0.6990008132 +9499 51.7709504877 -0.6952459922 +9500 51.7736907313 -0.6919273283 +9501 51.7766280679 -0.6890800359 +9502 51.7797313962 -0.6867343573 +9503 51.7829678504 -0.6849152393 +9504 51.786303148 -0.6836420659 +9505 51.7897019518 -0.682928448 +9506 51.7931282437 -0.6827820746 +9507 51.7965457063 -0.6832046259 +9508 51.7999181077 -0.68419175 +9509 51.8032096856 -0.6857331038 +9510 51.8063855272 -0.6878124574 +9511 51.8094119403 -0.6904078618 +9512 51.8122568112 -0.6934918771 +9513 51.8148899469 -0.6970318608 +9514 51.8172833964 -0.7009903115 +9515 51.819411749 -0.7053252657 +9516 51.8212524049 -0.7099907421 +9517 51.8227858168 -0.7149372311 +9518 51.8239956984 -0.7201122213 +9519 51.8248691985 -0.7254607596 +9520 51.825397038 -0.7309260379 +9521 51.8255736098 -0.73645 +9522 51.7445320556 -0.7558487222 +9523 51.7596761944 -0.7472673333 +9524 51.760413542 -0.7519601648 +9525 51.7614102361 -0.7565269625 +9526 51.7626581667 -0.7609306111 +9527 51.7475157222 -0.7695065 +9528 51.7445320556 -0.7558487222 +9529 51.8400288889 -0.7170165 +9530 51.8248898889 -0.7256216944 +9531 51.8241517558 -0.7209224785 +9532 51.8231539352 -0.7163499724 +9533 51.8219045833 -0.7119414722 +9534 51.83704525 -0.7033307222 +9535 51.8400288889 -0.7170165 +9536 51.7708836389 -0.8080578056 +9537 51.7762662222 -0.78350425 +9538 51.7789628325 -0.7856425451 +9539 51.781768038 -0.7873803361 +9540 51.784659 -0.7887033889 +9541 51.7793601944 -0.8128740833 +9542 51.7708836389 -0.8080578056 +9543 51.8112181389 -0.6671238889 +9544 51.8066635556 -0.6880245278 +9545 51.803896992 -0.6861315652 +9546 51.8010358551 -0.6846489466 +9547 51.7981034722 -0.6835886944 +9548 51.8027416389 -0.6623042222 +9549 51.8112181389 -0.6671238889 +9550 51.3813205885 -0.5587083333 +9551 51.3811440053 -0.5641786514 +9552 51.3806161316 -0.5695908576 +9553 51.3797425749 -0.5748874614 +9554 51.3785326144 -0.580012208 +9555 51.3769991016 -0.5849106794 +9556 51.3751583236 -0.5895308752 +9557 51.3730298284 -0.593823767 +9558 51.3706362166 -0.5977438204 +9559 51.3680029 -0.6012494788 +9560 51.3651578309 -0.604303604 +9561 51.362131204 -0.6068738693 +9562 51.3589551344 -0.6089330994 +9563 51.3556633166 -0.6104595561 +9564 51.3522906655 -0.6114371648 +9565 51.3488729457 -0.6118556802 +9566 51.3454463918 -0.61171079 +9567 51.3420473242 -0.6110041553 +9568 51.3387117637 -0.6097433881 +9569 51.3354750507 -0.6079419647 +9570 51.3323714709 -0.605619079 +9571 51.329433893 -0.6027994342 +9572 51.3266934217 -0.5995129781 +9573 51.3241790693 -0.5957945826 +9574 51.3219174496 -0.5916836731 +9575 51.3199324978 -0.5872238101 +9576 51.3182452181 -0.5824622279 +9577 51.3168734627 -0.5774493358 +9578 51.3158317441 -0.5722381866 +9579 51.3151310822 -0.5668839175 +9580 51.3147788885 -0.5614431705 +9581 51.3147788885 -0.5559734962 +9582 51.3151310822 -0.5505327491 +9583 51.3158317441 -0.5451784801 +9584 51.3168734627 -0.5399673309 +9585 51.3182452181 -0.5349544388 +9586 51.3199324978 -0.5301928566 +9587 51.3219174496 -0.5257329936 +9588 51.3241790693 -0.5216220841 +9589 51.3266934217 -0.5179036886 +9590 51.329433893 -0.5146172324 +9591 51.3323714709 -0.5117975877 +9592 51.3354750507 -0.5094747019 +9593 51.3387117637 -0.5076732786 +9594 51.3420473242 -0.5064125113 +9595 51.3454463918 -0.5057058767 +9596 51.3488729457 -0.5055609864 +9597 51.3522906655 -0.5059795018 +9598 51.3556633166 -0.5069571105 +9599 51.3589551344 -0.5084835673 +9600 51.362131204 -0.5105427974 +9601 51.3651578309 -0.5131130626 +9602 51.3680029 -0.5161671879 +9603 51.3706362166 -0.5196728463 +9604 51.3730298284 -0.5235928997 +9605 51.3751583236 -0.5278857915 +9606 51.3769991016 -0.5325059873 +9607 51.3785326144 -0.5374044587 +9608 51.3797425749 -0.5425292053 +9609 51.3806161316 -0.5478258091 +9610 51.3811440053 -0.5532380153 +9611 51.3813205885 -0.5587083333 +9612 51.318625 -0.6199333333 +9613 51.3266777222 -0.5994920556 +9614 51.3290671078 -0.6023993034 +9615 51.3316109024 -0.6049511893 +9616 51.3342884167 -0.6071268889 +9617 51.3262388889 -0.6275583333 +9618 51.318625 -0.6199333333 +9619 51.3775888889 -0.4969416667 +9620 51.3693692222 -0.5178943056 +9621 51.3669779903 -0.5149878589 +9622 51.3644324142 -0.5124379479 +9623 51.36175325 -0.5102653056 +9624 51.369975 -0.4893055556 +9625 51.3775888889 -0.4969416667 +9626 51.6217164382 -0.5129944444 +9627 51.6215398612 -0.5184936191 +9628 51.621012006 -0.5239343742 +9629 51.6201384801 -0.5292589149 +9630 51.6189285623 -0.5344106889 +9631 51.6173951042 -0.5393349903 +9632 51.6155543924 -0.5439795438 +9633 51.6134259744 -0.5482950621 +9634 51.6110324506 -0.5522357706 +9635 51.608399232 -0.5557598936 +9636 51.6055542703 -0.5588300976 +9637 51.6025277593 -0.5614138859 +9638 51.5993518132 -0.5634839411 +9639 51.5960601253 -0.5650184115 +9640 51.5926876095 -0.5660011389 +9641 51.589270029 -0.5664218254 +9642 51.585843617 -0.5662761375 +9643 51.5824446922 -0.5655657464 +9644 51.5791092741 -0.5642983057 +9645 51.5758727012 -0.5624873639 +9646 51.5727692576 -0.5601522173 +9647 51.5698318103 -0.5573177001 +9648 51.5670914623 -0.5540139185 +9649 51.5645772242 -0.5502759287 +9650 51.5623157084 -0.5461433639 +9651 51.5603308485 -0.5416600139 +9652 51.5586436476 -0.5368733613 +9653 51.5572719567 -0.5318340803 +9654 51.5562302872 -0.5265955023 +9655 51.5555296584 -0.5212130539 +9656 51.5551774815 -0.5157436739 +9657 51.5551774815 -0.510245215 +9658 51.5555296584 -0.504775835 +9659 51.5562302872 -0.4993933866 +9660 51.5572719567 -0.4941548086 +9661 51.5586436476 -0.4891155276 +9662 51.5603308485 -0.484328875 +9663 51.5623157084 -0.4798455249 +9664 51.5645772242 -0.4757129602 +9665 51.5670914623 -0.4719749703 +9666 51.5698318103 -0.4686711888 +9667 51.5727692576 -0.4658366716 +9668 51.5758727012 -0.4635015249 +9669 51.5791092741 -0.4616905832 +9670 51.5824446922 -0.4604231424 +9671 51.585843617 -0.4597127514 +9672 51.589270029 -0.4595670635 +9673 51.5926876095 -0.4599877499 +9674 51.5960601253 -0.4609704774 +9675 51.5993518132 -0.4625049477 +9676 51.6025277593 -0.464575003 +9677 51.6055542703 -0.4671587913 +9678 51.608399232 -0.4702289953 +9679 51.6110324506 -0.4737531183 +9680 51.6134259744 -0.4776938267 +9681 51.6155543924 -0.4820093451 +9682 51.6173951042 -0.4866538986 +9683 51.6189285623 -0.4915782 +9684 51.6201384801 -0.4967299739 +9685 51.621012006 -0.5020545147 +9686 51.6215398612 -0.5074952698 +9687 51.6217164382 -0.5129944444 +9688 51.5599277778 -0.5756055556 +9689 51.56767425 -0.5547771667 +9690 51.5701051677 -0.5576101111 +9691 51.5726852958 -0.5600801312 +9692 51.5753936389 -0.5621670833 +9693 51.56765 -0.5829861111 +9694 51.5599277778 -0.5756055556 +9695 51.6166444444 -0.450975 +9696 51.60916325 -0.4711767778 +9697 51.6067302115 -0.4683454519 +9698 51.6041480831 -0.4658782366 +9699 51.6014379167 -0.4637951944 +9700 51.6089222222 -0.4435833333 +9701 51.6166444444 -0.450975 +9702 51.6064472222 -0.5820527778 +9703 51.6001324167 -0.5630313056 +9704 51.6028946338 -0.5611342148 +9705 51.6055390603 -0.5588447291 +9706 51.6080441389 -0.5561814444 +9707 51.614375 -0.57525 +9708 51.6064472222 -0.5820527778 +9709 51.570975 -0.4448222222 +9710 51.5769761389 -0.4628163333 +9711 51.5742051095 -0.464678404 +9712 51.5715499091 -0.4669335187 +9713 51.5690321389 -0.4695632778 +9714 51.5630472222 -0.4516166667 +9715 51.570975 -0.4448222222 +9716 51.519198392 -0.46135 +9717 51.5190207088 -0.4675046258 +9718 51.5184891791 -0.4736065998 +9719 51.5176083498 -0.4796037246 +9720 51.5163857558 -0.4854447066 +9721 51.5148318544 -0.4910795983 +9722 51.5129599359 -0.4964602286 +9723 51.5107860084 -0.5015406165 +9724 51.5083286606 -0.5062773666 +9725 51.5056089011 -0.5106300405 +9726 51.5026499783 -0.5145615031 +9727 51.4994771803 -0.5180382389 +9728 51.4961176176 -0.5210306378 +9729 51.4925999902 -0.5235132452 +9730 51.4889543421 -0.525464977 +9731 51.4852118033 -0.526869296 +9732 51.4814043233 -0.5277143491 +9733 51.4775643984 -0.5279930642 +9734 51.4737247933 -0.5277032056 +9735 51.4699182621 -0.5268473884 +9736 51.4661772686 -0.5254330514 +9737 51.4625337097 -0.5234723888 +9738 51.4590186443 -0.5209822419 +9739 51.4556620291 -0.5179839515 +9740 51.4524924637 -0.5145031729 +9741 51.4495369488 -0.510569654 +9742 51.4468206561 -0.5062169801 +9743 51.4443667159 -0.5014822864 +9744 51.4421960211 -0.4964059411 +9745 51.4403270501 -0.4910312023 +9746 51.4387757108 -0.4854038501 +9747 51.4375552059 -0.479571799 +9748 51.436675922 -0.4735846922 +9749 51.436145341 -0.4674934822 +9750 51.4359679776 -0.46135 +9751 51.436145341 -0.4552065178 +9752 51.436675922 -0.4491153078 +9753 51.4375552059 -0.443128201 +9754 51.4387757108 -0.4372961499 +9755 51.4403270501 -0.4316687977 +9756 51.4421960211 -0.4262940589 +9757 51.4443667159 -0.4212177136 +9758 51.4468206561 -0.4164830199 +9759 51.4495369488 -0.412130346 +9760 51.4524924637 -0.4081968271 +9761 51.4556620291 -0.4047160485 +9762 51.4590186443 -0.4017177581 +9763 51.4625337097 -0.3992276112 +9764 51.4661772686 -0.3972669486 +9765 51.4699182621 -0.3958526116 +9766 51.4737247933 -0.3949967944 +9767 51.4775643984 -0.3947069358 +9768 51.4814043233 -0.3949856509 +9769 51.4852118033 -0.395830704 +9770 51.4889543421 -0.397235023 +9771 51.4925999902 -0.3991867548 +9772 51.4961176176 -0.4016693622 +9773 51.4994771803 -0.4046617611 +9774 51.5026499783 -0.4081384969 +9775 51.5056089011 -0.4120699595 +9776 51.5083286606 -0.4164226334 +9777 51.5107860084 -0.4211593835 +9778 51.5129599359 -0.4262397714 +9779 51.5148318544 -0.4316204017 +9780 51.5163857558 -0.4372552934 +9781 51.5176083498 -0.4430962754 +9782 51.5184891791 -0.4490934002 +9783 51.5190207088 -0.4551953742 +9784 51.519198392 -0.46135 +9785 51.4704933333 -0.5569003333 +9786 51.4706154722 -0.5270472778 +9787 51.473972328 -0.5277391047 +9788 51.4773531895 -0.5279918993 +9789 51.4807356961 -0.527803899 +9790 51.4840974722 -0.52717625 +9791 51.4839753889 -0.5570173333 +9792 51.4704933333 -0.5569003333 +9793 51.4846374722 -0.3613735833 +9794 51.4845450833 -0.3956410556 +9795 51.4811877781 -0.3949547368 +9796 51.4778067502 -0.3947077047 +9797 51.4744243673 -0.3949014836 +9798 51.471063 -0.3955346944 +9799 51.4711554167 -0.3612565833 +9800 51.4846374722 -0.3613735833 +9801 51.45779225 -0.5542044167 +9802 51.4579273056 -0.5200781389 +9803 51.4611347825 -0.5225554954 +9804 51.4644627941 -0.5245850906 +9805 51.4678869878 -0.5261519863 +9806 51.4713823056 -0.5272446111 +9807 51.4712743611 -0.5543178889 +9808 51.45779225 -0.5542044167 +9809 51.4719051944 -0.3622085 +9810 51.4718188333 -0.3953535278 +9811 51.4683164757 -0.3963867682 +9812 51.4648821005 -0.397895493 +9813 51.4615408393 -0.3998685359 +9814 51.4583171389 -0.4022913611 +9815 51.4584231111 -0.3620950278 +9816 51.4719051944 -0.3622085 +9817 51.5860694194 -0.4197222222 +9818 51.5858928414 -0.4252170925 +9819 51.5853649835 -0.4306535891 +9820 51.584491453 -0.4359739627 +9821 51.5832815289 -0.4411217051 +9822 51.5817480627 -0.4460421536 +9823 51.5799073411 -0.4506830738 +9824 51.5777789117 -0.4549952171 +9825 51.5753853748 -0.4589328445 +9826 51.5727521418 -0.4624542133 +9827 51.5699071642 -0.4655220189 +9828 51.5668806359 -0.4681037901 +9829 51.5637046715 -0.4701722306 +9830 51.5604129644 -0.4717055057 +9831 51.5570404286 -0.4726874696 +9832 51.5536228274 -0.4731078322 +9833 51.5501963944 -0.4729622633 +9834 51.5467974485 -0.4722524326 +9835 51.5434620093 -0.4709859873 +9836 51.5402254156 -0.4691764654 +9837 51.5371219518 -0.4668431476 +9838 51.5341844852 -0.4640108489 +9839 51.5314441189 -0.4607096516 +9840 51.5289298638 -0.4569745846 +9841 51.5266683326 -0.45284525 +9842 51.5246834591 -0.4483654033 +9843 51.5229962465 -0.4435824903 +9844 51.521624546 -0.4385471456 +9845 51.5205828693 -0.4333126589 +9846 51.5198822356 -0.4279344138 +9847 51.5195300562 -0.4224693049 +9848 51.5195300562 -0.4169751395 +9849 51.5198822356 -0.4115100306 +9850 51.5205828693 -0.4061317855 +9851 51.521624546 -0.4008972988 +9852 51.5229962465 -0.3958619541 +9853 51.5246834591 -0.3910790411 +9854 51.5266683326 -0.3865991945 +9855 51.5289298638 -0.3824698599 +9856 51.5314441189 -0.3787347928 +9857 51.5341844852 -0.3754335956 +9858 51.5371219518 -0.3726012968 +9859 51.5402254156 -0.3702679791 +9860 51.5434620093 -0.3684584572 +9861 51.5467974485 -0.3671920118 +9862 51.5501963944 -0.3664821812 +9863 51.5536228274 -0.3663366122 +9864 51.5570404286 -0.3667569749 +9865 51.5604129644 -0.3677389388 +9866 51.5637046715 -0.3692722138 +9867 51.5668806359 -0.3713406543 +9868 51.5699071642 -0.3739224255 +9869 51.5727521418 -0.3769902312 +9870 51.5753853748 -0.3805115999 +9871 51.5777789117 -0.3844492274 +9872 51.5799073411 -0.3887613706 +9873 51.5817480627 -0.3934022908 +9874 51.5832815289 -0.3983227393 +9875 51.584491453 -0.4034704818 +9876 51.5853649835 -0.4087908553 +9877 51.5858928414 -0.414227352 +9878 51.5860694194 -0.4197222222 +9879 51.5306527778 -0.4949055556 +9880 51.53710075 -0.466825 +9881 51.5398120238 -0.468901124 +9882 51.5426289526 -0.4705770388 +9883 51.5455286111 -0.4718390278 +9884 51.5390916667 -0.4998722222 +9885 51.5306527778 -0.4949055556 +9886 51.5750055556 -0.3429888889 +9887 51.5682804444 -0.3724551111 +9888 51.5655610198 -0.3704066466 +9889 51.5627375531 -0.3687601003 +9890 51.5598330556 -0.3675288056 +9891 51.5665694444 -0.3380138889 +9892 51.5750055556 -0.3429888889 +9893 51.9162427857 -0.3684444444 +9894 51.9160651122 -0.3746532062 +9895 51.9155336117 -0.3808088511 +9896 51.9146528312 -0.3868587204 +9897 51.9134303051 -0.3927510676 +9898 51.9118764909 -0.3984355044 +9899 51.9100046782 -0.4038634347 +9900 51.9078308751 -0.4089884723 +9901 51.9053736697 -0.4137668395 +9902 51.90265407 -0.4181577423 +9903 51.8996953238 -0.4221237194 +9904 51.8965227181 -0.4256309617 +9905 51.8931633624 -0.4286495997 +9906 51.8896459557 -0.4311539569 +9907 51.8860005403 -0.4331227659 +9908 51.8822582448 -0.4345393464 +9909 51.8784510169 -0.4353917437 +9910 51.8746113507 -0.4356728262 +9911 51.870772009 -0.4353803413 +9912 51.8669657435 -0.4345169299 +9913 51.8632250155 -0.4330900986 +9914 51.8595817194 -0.4311121514 +9915 51.8560669116 -0.4286000794 +9916 51.8527105458 -0.4255754131 +9917 51.8495412194 -0.4220640341 +9918 51.8465859299 -0.4180959529 +9919 51.8438698469 -0.41370505 +9920 51.8414160983 -0.408928787 +9921 51.8392455744 -0.4038078861 +9922 51.8373767517 -0.3983859841 +9923 51.8358255363 -0.3927092619 +9924 51.8346051295 -0.386826053 +9925 51.8337259165 -0.3807864345 +9926 51.8331953784 -0.3746418038 +9927 51.8330180294 -0.3684444444 +9928 51.8331953784 -0.3622470851 +9929 51.8337259165 -0.3561024544 +9930 51.8346051295 -0.3500628358 +9931 51.8358255363 -0.344179627 +9932 51.8373767517 -0.3385029048 +9933 51.8392455744 -0.3330810028 +9934 51.8414160983 -0.3279601019 +9935 51.8438698469 -0.3231838389 +9936 51.8465859299 -0.318792936 +9937 51.8495412194 -0.3148248548 +9938 51.8527105458 -0.3113134758 +9939 51.8560669116 -0.3082888095 +9940 51.8595817194 -0.3057767375 +9941 51.8632250155 -0.3037987903 +9942 51.8669657435 -0.302371959 +9943 51.870772009 -0.3015085476 +9944 51.8746113507 -0.3012160627 +9945 51.8784510169 -0.3014971452 +9946 51.8822582448 -0.3023495425 +9947 51.8860005403 -0.303766123 +9948 51.8896459557 -0.3057349319 +9949 51.8931633624 -0.3082392892 +9950 51.8965227181 -0.3112579272 +9951 51.8996953238 -0.3147651695 +9952 51.90265407 -0.3187311466 +9953 51.9053736697 -0.3231220494 +9954 51.9078308751 -0.3279004166 +9955 51.9100046782 -0.3330254542 +9956 51.9118764909 -0.3384533845 +9957 51.9134303051 -0.3441378213 +9958 51.9146528312 -0.3500301685 +9959 51.9155336117 -0.3560800378 +9960 51.9160651122 -0.3622356827 +9961 51.9162427857 -0.3684444444 +9962 51.8555694444 -0.4515333333 +9963 51.8591609444 -0.4308439444 +9964 51.8619845779 -0.4324842643 +9965 51.8648740476 -0.4337918297 +9966 51.8678143333 -0.4347598056 +9967 51.864225 -0.4554361111 +9968 51.8555694444 -0.4515333333 +9969 51.8934305556 -0.2864888889 +9970 51.8900711944 -0.3060048333 +9971 51.8872457884 -0.3043708809 +9972 51.8843548473 -0.3030704243 +9973 51.8814134167 -0.3021101667 +9974 51.884775 -0.2825805556 +9975 51.8934305556 -0.2864888889 +9976 51.6891160539 -0.32585 +9977 51.6889394786 -0.3313573375 +9978 51.6884116286 -0.3368061684 +9979 51.6875381112 -0.3421386119 +9980 51.6863282054 -0.3472980312 +9981 51.6847947626 -0.3522296393 +9982 51.6829540693 -0.356881083 +9983 51.680825673 -0.3612030018 +9984 51.6784321737 -0.365149553 +9985 51.6757989826 -0.3686788992 +9986 51.672954051 -0.3717536515 +9987 51.6699275723 -0.3743412651 +9988 51.6667516608 -0.3764143825 +9989 51.6634600093 -0.3779511197 +9990 51.6600875314 -0.378935295 +9991 51.6566699898 -0.3793565956 +9992 51.6532436176 -0.3792106819 +9993 51.6498447329 -0.3784992283 +9994 51.6465093546 -0.3772298997 +9995 51.6432728209 -0.3754162654 +9996 51.6401694155 -0.3730776505 +9997 51.6372320048 -0.3702389262 +9998 51.6344916913 -0.3669302437 +9999 51.6319774852 -0.3631867112 +10000 51.6297159985 -0.3590480206 +10001 51.6277311645 -0.3545580267 +10002 51.6260439856 -0.3497642823 +10003 51.6246723128 -0.3447175366 +10004 51.6236306571 -0.3394711997 +10005 51.6229300376 -0.3340807801 +10006 51.6225778653 -0.3286033007 +10007 51.6225778653 -0.3230966993 +10008 51.6229300376 -0.3176192199 +10009 51.6236306571 -0.3122288003 +10010 51.6246723128 -0.3069824634 +10011 51.6260439856 -0.3019357177 +10012 51.6277311645 -0.2971419733 +10013 51.6297159985 -0.2926519794 +10014 51.6319774852 -0.2885132888 +10015 51.6344916913 -0.2847697563 +10016 51.6372320048 -0.2814610738 +10017 51.6401694155 -0.2786223495 +10018 51.6432728209 -0.2762837346 +10019 51.6465093546 -0.2744701003 +10020 51.6498447329 -0.2732007717 +10021 51.6532436176 -0.2724893181 +10022 51.6566699898 -0.2723434044 +10023 51.6600875314 -0.272764705 +10024 51.6634600093 -0.2737488803 +10025 51.6667516608 -0.2752856175 +10026 51.6699275723 -0.2773587349 +10027 51.672954051 -0.2799463485 +10028 51.6757989826 -0.2830211008 +10029 51.6784321737 -0.286550447 +10030 51.680825673 -0.2904969982 +10031 51.6829540693 -0.294818917 +10032 51.6847947626 -0.2994703607 +10033 51.6863282054 -0.3044019688 +10034 51.6875381112 -0.3095613881 +10035 51.6884116286 -0.3148938316 +10036 51.6889394786 -0.3203426625 +10037 51.6891160539 -0.32585 +10038 51.6427944444 -0.40025 +10039 51.6454770833 -0.3767162778 +10040 51.6483711888 -0.3780102409 +10041 51.6513260665 -0.3788797194 +10042 51.6543176667 -0.3793175556 +10043 51.6516361111 -0.4028416667 +10044 51.6427944444 -0.40025 +10045 51.6688083333 -0.251425 +10046 51.6661527222 -0.2749615278 +10047 51.6632575555 -0.2736733649 +10048 51.6603019573 -0.2728102231 +10049 51.65731 -0.2723790556 +10050 51.6599666667 -0.2488333333 +10051 51.6688083333 -0.251425 +10052 51.1896729688 -0.1902777778 +10053 51.1894952774 -0.1963884086 +10054 51.1889637232 -0.2024467658 +10055 51.1880828533 -0.2084010264 +10056 51.1868602024 -0.214200265 +10057 51.1853062283 -0.2197948925 +10058 51.1834342212 -0.225137083 +10059 51.1812601899 -0.2301811851 +10060 51.1788027231 -0.2348841136 +10061 51.1760828302 -0.2392057194 +10062 51.1731237601 -0.2431091322 +10063 51.1699508017 -0.2465610756 +10064 51.1665910662 -0.2495321498 +10065 51.1630732549 -0.2519970809 +10066 51.1594274128 -0.2539349337 +10067 51.1556846713 -0.2553292873 +10068 51.1518769815 -0.2561683713 +10069 51.1480368411 -0.2564451617 +10070 51.1441970168 -0.2561574367 +10071 51.1403902646 -0.2553077906 +10072 51.1366490502 -0.2539036069 +10073 51.1330052727 -0.2519569908 +10074 51.1294899933 -0.2494846615 +10075 51.1261331707 -0.2465078063 +10076 51.1229634069 -0.243051896 +10077 51.1200077046 -0.2391464653 +10078 51.1172912377 -0.2348248596 +10079 51.1148371386 -0.2301239488 +10080 51.1126663019 -0.2250838137 +10081 51.1107972077 -0.2197474041 +10082 51.1092457655 -0.2141601747 +10083 51.1080251793 -0.2083696995 +10084 51.1071458364 -0.202425269 +10085 51.1066152198 -0.1963774741 +10086 51.1064378445 -0.1902777778 +10087 51.1066152198 -0.1841780815 +10088 51.1071458364 -0.1781302865 +10089 51.1080251793 -0.1721858561 +10090 51.1092457655 -0.1663953808 +10091 51.1107972077 -0.1608081514 +10092 51.1126663019 -0.1554717418 +10093 51.1148371386 -0.1504316067 +10094 51.1172912377 -0.145730696 +10095 51.1200077046 -0.1414090902 +10096 51.1229634069 -0.1375036596 +10097 51.1261331707 -0.1340477492 +10098 51.1294899933 -0.131070894 +10099 51.1330052727 -0.1285985648 +10100 51.1366490502 -0.1266519486 +10101 51.1403902646 -0.1252477649 +10102 51.1441970168 -0.1243981188 +10103 51.1480368411 -0.1241103939 +10104 51.1518769815 -0.1243871843 +10105 51.1556846713 -0.1252262682 +10106 51.1594274128 -0.1266206218 +10107 51.1630732549 -0.1285584746 +10108 51.1665910662 -0.1310234057 +10109 51.1699508017 -0.13399448 +10110 51.1731237601 -0.1374464234 +10111 51.1760828302 -0.1413498362 +10112 51.1788027231 -0.1456714419 +10113 51.1812601899 -0.1503743705 +10114 51.1834342212 -0.1554184725 +10115 51.1853062283 -0.1607606631 +10116 51.1868602024 -0.1663552906 +10117 51.1880828533 -0.1721545292 +10118 51.1889637232 -0.1781087898 +10119 51.1894952774 -0.1841671469 +10120 51.1896729688 -0.1902777778 +10121 51.1334722222 -0.2763583333 +10122 51.1365861111 -0.2538749722 +10123 51.1395019494 -0.2550266082 +10124 51.1424624516 -0.255840969 +10125 51.1454521944 -0.25631375 +10126 51.1422527778 -0.2794138889 +10127 51.1334722222 -0.2763583333 +10128 51.1650083333 -0.1143222222 +10129 51.1630574722 -0.1285487778 +10130 51.1602170511 -0.126990203 +10131 51.1573133081 -0.1257617811 +10132 51.1543613889 -0.1248698611 +10133 51.1562277778 -0.1112583333 +10134 51.1650083333 -0.1143222222 +10135 51.1318138889 -0.2750777778 +10136 51.1348706667 -0.2530278889 +10137 51.1377494398 -0.2543771033 +10138 51.1406818913 -0.2553931703 +10139 51.1436527778 -0.25607075 +10140 51.1405944444 -0.2781333333 +10141 51.1318138889 -0.2750777778 +10142 51.1646583333 -0.1036388889 +10143 51.1613735 -0.1275807778 +10144 51.1584972883 -0.1262195947 +10145 51.1555668638 -0.1251916959 +10146 51.1525974722 -0.1245023611 +10147 51.1558805556 -0.100575 +10148 51.1646583333 -0.1036388889 +10149 51.1927777778 -0.18 +10150 51.2083333333 -0.0863888889 +10151 51.2117007276 -0.0857783081 +10152 51.2150907095 -0.0857454411 +10153 51.2184651944 -0.0862619904 +10154 51.2217891473 -0.0873227125 +10155 51.2250280504 -0.0889167081 +10156 51.2281482618 -0.091027531 +10157 51.231117366 -0.0936333542 +10158 51.2339045112 -0.0967071931 +10159 51.2364807312 -0.1002171832 +10160 51.2388192469 -0.1041269087 +10161 51.2408957465 -0.1083957801 +10162 51.242688639 -0.1129794553 +10163 51.24417928 -0.1178303017 +10164 51.2453521666 -0.1228978922 +10165 51.2461950995 -0.1281295323 +10166 51.2466993108 -0.1334708104 +10167 51.2468595556 -0.1388661674 +10168 51.246674167 -0.144259478 +10169 51.2461450733 -0.1495946383 +10170 51.2452777785 -0.1548161531 +10171 51.2440813036 -0.1598697169 +10172 51.2425680934 -0.1647027819 +10173 51.2407538854 -0.1692651072 +10174 51.2386575454 -0.1735092831 +10175 51.2363008705 -0.1773912259 +10176 51.233708361 -0.1808706361 +10177 51.230906965 -0.1839114173 +10178 51.2279257965 -0.1864820495 +10179 51.2247958322 -0.1885559151 +10180 51.2215495885 -0.1901115721 +10181 51.2182207829 -0.1911329731 +10182 51.2148439831 -0.1916096276 +10183 51.2114542476 -0.1915367066 +10184 51.2080867616 -0.1909150876 +10185 51.2047764719 -0.1897513404 +10186 51.2015577241 -0.1880576543 +10187 51.1984639072 -0.1858517068 +10188 51.1955271077 -0.1831564762 +10189 51.1927777778 -0.18 +10190 51.1971527778 -0.2102416667 +10191 51.2010925556 -0.1877980556 +10192 51.2039255796 -0.1893926122 +10193 51.2068373717 -0.1905742304 +10194 51.2098042222 -0.1913332222 +10195 51.2058111111 -0.2140805556 +10196 51.1971527778 -0.2102416667 +10197 51.231575 -0.0667972222 +10198 51.2274489722 -0.0904669444 +10199 51.2246628442 -0.0886741747 +10200 51.2217865477 -0.0872889642 +10201 51.2188435278 -0.0863225278 +10202 51.2229166667 -0.0629555556 +10203 51.231575 -0.0667972222 +10204 51.1962361111 -0.2119305556 +10205 51.2004910278 -0.1873991111 +10206 51.2033034861 -0.18908136 +10207 51.2061997519 -0.1903533425 +10208 51.20915625 -0.1912046389 +10209 51.2049027778 -0.2157277778 +10210 51.1962361111 -0.2119305556 +10211 51.2308888889 -0.0653694444 +10212 51.22666225 -0.0899130833 +10213 51.2238484928 -0.0882358648 +10214 51.2209512348 -0.0869696108 +10215 51.2179940833 -0.0861245556 +10216 51.2222222222 -0.0615722222 +10217 51.2308888889 -0.0653694444 +10218 51.2626111111 -0.1465555556 +10219 51.2464652222 -0.1470106389 +10220 51.2468036602 -0.1422509249 +10221 51.2468710493 -0.1374619454 +10222 51.2466668333 -0.1326828333 +10223 51.2624527778 -0.1322333333 +10224 51.2626111111 -0.1465555556 +10225 51.1662944444 -0.1349666667 +10226 51.2004327778 -0.1339975833 +10227 51.19804275 -0.1483735833 +10228 51.1664555556 -0.1492611111 +10229 51.1662944444 -0.1349666667 +10230 51.1962888889 -0.2073083333 +10231 51.1998197778 -0.1869276111 +10232 51.2026087033 -0.1887082862 +10233 51.2054871169 -0.1900816288 +10234 51.2084315833 -0.1910363889 +10235 51.2049555556 -0.2111 +10236 51.1962888889 -0.2073083333 +10237 51.2291944444 -0.0707138889 +10238 51.2259695 -0.0894569722 +10239 51.2231321936 -0.0878808339 +10240 51.2202171888 -0.0867187109 +10241 51.21724825 -0.0859799722 +10242 51.2205277778 -0.0669194444 +10243 51.2291944444 -0.0707138889 +10244 51.2578166667 -0.157575 +10245 51.2449930556 -0.1562663333 +10246 51.2458686873 -0.1516398746 +10247 51.2464759748 -0.146905405 +10248 51.2468101389 -0.1421024444 +10249 51.2583888889 -0.1432805556 +10250 51.2578166667 -0.157575 +10251 51.1672388889 -0.1340222222 +10252 51.1998783889 -0.1373332778 +10253 51.1975344444 -0.1514294722 +10254 51.1666666667 -0.1482888889 +10255 51.1672388889 -0.1340222222 +10256 51.3724494398 0.0325 +10257 51.372271753 0.02636507 +10258 51.3717402124 0.0202826224 +10259 51.370859365 0.0143046872 +10260 51.3696367457 0.008482393 +10261 51.368082812 0.0028655268 +10262 51.3662108541 -0.0024978947 +10263 51.3640368805 -0.0075620381 +10264 51.3615794797 -0.012283647 +10265 51.3588596609 -0.0166224123 +10266 51.3559006727 -0.0205413175 +10267 51.3527278033 -0.0240069543 +10268 51.3493681637 -0.0269898066 +10269 51.3458504545 -0.0294645007 +10270 51.3422047201 -0.0314100192 +10271 51.3384620911 -0.0328098769 +10272 51.3346545178 -0.0336522578 +10273 51.330814497 -0.0339301114 +10274 51.3269747944 -0.033641208 +10275 51.3231681648 -0.0327881536 +10276 51.3194270729 -0.0313783621 +10277 51.3157834167 -0.0294239879 +10278 51.3122682561 -0.0269418177 +10279 51.3089115485 -0.0239531235 +10280 51.3057418948 -0.0204834779 +10281 51.3027862964 -0.0165625336 +10282 51.3000699262 -0.0122237683 +10283 51.2976159153 -0.0075041985 +10284 51.2954451573 -0.0024440638 +10285 51.2935761314 0.0029135158 +10286 51.2920247463 0.0085229059 +10287 51.2908042052 0.0143363443 +10288 51.289924895 0.0203043458 +10289 51.2893942982 0.0263761198 +10290 51.2892169295 0.0325 +10291 51.2893942982 0.0386238802 +10292 51.289924895 0.0446956542 +10293 51.2908042052 0.0506636557 +10294 51.2920247463 0.0564770941 +10295 51.2935761314 0.0620864842 +10296 51.2954451573 0.0674440638 +10297 51.2976159153 0.0725041985 +10298 51.3000699262 0.0772237683 +10299 51.3027862964 0.0815625336 +10300 51.3057418948 0.0854834779 +10301 51.3089115485 0.0889531235 +10302 51.3122682561 0.0919418177 +10303 51.3157834167 0.0944239879 +10304 51.3194270729 0.0963783621 +10305 51.3231681648 0.0977881536 +10306 51.3269747944 0.098641208 +10307 51.330814497 0.0989301114 +10308 51.3346545178 0.0986522578 +10309 51.3384620911 0.0978098769 +10310 51.3422047201 0.0964100192 +10311 51.3458504545 0.0944645007 +10312 51.3493681637 0.0919898066 +10313 51.3527278033 0.0890069543 +10314 51.3559006727 0.0855413175 +10315 51.3588596609 0.0816224123 +10316 51.3615794797 0.077283647 +10317 51.3640368805 0.0725620381 +10318 51.3662108541 0.0674978947 +10319 51.368082812 0.0621344732 +10320 51.3696367457 0.056517607 +10321 51.370859365 0.0506953128 +10322 51.3717402124 0.0447173776 +10323 51.372271753 0.03863493 +10324 51.3724494398 0.0325 +10325 51.2832027778 0.0037444444 +10326 51.2916319722 0.0102089167 +10327 51.2927401761 0.0057608933 +10328 51.2940463129 0.0014515666 +10329 51.2955436111 -0.0026966944 +10330 51.2871 -0.0091694444 +10331 51.2832027778 0.0037444444 +10332 51.3806944444 0.0627277778 +10333 51.3700889167 0.0545643611 +10334 51.368990418 0.05902709 +10335 51.3676932629 0.0633514721 +10336 51.3662042222 0.0675149722 +10337 51.3767972222 0.0756722222 +10338 51.3806944444 0.0627277778 +10339 51.5385224685 0.0551777778 +10340 51.5383458893 0.049688635 +10341 51.5378180277 0.0442578048 +10342 51.5369444912 0.0389429762 +10343 51.5357345586 0.0338005981 +10344 51.5342010816 0.0288852764 +10345 51.5323603469 0.0242491907 +10346 51.5302319023 0.0199415384 +10347 51.527838348 0.0160080105 +10348 51.5252050956 0.0124903067 +10349 51.5223600968 0.0094256923 +10350 51.5193335456 0.0068466052 +10351 51.5161575568 0.0047803132 +10352 51.512865824 0.0032486287 +10353 51.5094932614 0.0022676808 +10354 51.5060756327 0.001847749 +10355 51.5026491717 0.0019931596 +10356 51.4992501975 0.0027022447 +10357 51.4959147301 0.0039673655 +10358 51.4926781088 0.0057749982 +10359 51.489574618 0.0081058824 +10360 51.4866371256 0.0109352292 +10361 51.4838967349 0.0142329877 +10362 51.4813824572 0.0179641657 +10363 51.4791209055 0.0220892021 +10364 51.4771360138 0.0265643871 +10365 51.4754487856 0.0313423241 +10366 51.4740770724 0.0363724312 +10367 51.473035386 0.0416014737 +10368 51.4723347457 0.0469741258 +10369 51.471982563 0.0524335517 +10370 51.471982563 0.0579220039 +10371 51.4723347457 0.0633814298 +10372 51.473035386 0.0687540818 +10373 51.4740770724 0.0739831244 +10374 51.4754487856 0.0790132314 +10375 51.4771360138 0.0837911685 +10376 51.4791209055 0.0882663534 +10377 51.4813824572 0.0923913899 +10378 51.4838967349 0.0961225678 +10379 51.4866371256 0.0994203263 +10380 51.489574618 0.1022496732 +10381 51.4926781088 0.1045805574 +10382 51.4959147301 0.1063881901 +10383 51.4992501975 0.1076533108 +10384 51.5026491717 0.1083623959 +10385 51.5060756327 0.1085078065 +10386 51.5094932614 0.1080878748 +10387 51.512865824 0.1071069268 +10388 51.5161575568 0.1055752423 +10389 51.5193335456 0.1035089504 +10390 51.5223600968 0.1009298632 +10391 51.5252050956 0.0978652489 +10392 51.527838348 0.094347545 +10393 51.5302319023 0.0904140172 +10394 51.5323603469 0.0861063648 +10395 51.5342010816 0.0814702792 +10396 51.5357345586 0.0765549574 +10397 51.5369444912 0.0714125794 +10398 51.5378180277 0.0660977508 +10399 51.5383458893 0.0606669206 +10400 51.5385224685 0.0551777778 +10401 51.5032755556 -0.0265288333 +10402 51.5023953889 0.0020265 +10403 51.5053971176 0.0018316307 +10404 51.5083975865 0.0020711489 +10405 51.5113723611 0.0027431944 +10406 51.5122523333 -0.0258050833 +10407 51.5032755556 -0.0265288333 +10408 51.5071330556 0.1372346667 +10409 51.5080571389 0.1083335278 +10410 51.5050552868 0.1085236627 +10411 51.5020549588 0.1082794163 +10412 51.4990805833 0.1076028611 +10413 51.4981562778 0.136511 +10414 51.5071330556 0.1372346667 +10415 51.6857966284 0.1560083333 +10416 51.685620053 0.1505013986 +10417 51.6850922028 0.1450529662 +10418 51.684218685 0.1397209126 +10419 51.6830087786 0.1345618705 +10420 51.681475335 0.129630623 +10421 51.6796346408 0.1249795192 +10422 51.6775062434 0.1206579162 +10423 51.6751127429 0.1167116533 +10424 51.6724795505 0.1131825649 +10425 51.6696346173 0.110108037 +10426 51.6666081371 0.1075206121 +10427 51.6634322239 0.1054476458 +10428 51.6601405706 0.1039110205 +10429 51.6567680908 0.1029269166 +10430 51.6533505473 0.1025056463 +10431 51.6499241731 0.1026515488 +10432 51.6465252864 0.1033629501 +10433 51.6431899062 0.1046321855 +10434 51.6399533706 0.1064456869 +10435 51.6368499633 0.1087841307 +10436 51.6339125508 0.1116226474 +10437 51.6311722356 0.1149310881 +10438 51.6286580279 0.1186743472 +10439 51.6263965398 0.1228127354 +10440 51.6244117045 0.1273024016 +10441 51.6227245245 0.132095796 +10442 51.6213528508 0.1371421734 +10443 51.6203111944 0.1423881274 +10444 51.6196105745 0.1477781538 +10445 51.619258402 0.1532552335 +10446 51.619258402 0.1587614331 +10447 51.6196105745 0.1642385129 +10448 51.6203111944 0.1696285392 +10449 51.6213528508 0.1748744933 +10450 51.6227245245 0.1799208706 +10451 51.6244117045 0.1847142651 +10452 51.6263965398 0.1892039312 +10453 51.6286580279 0.1933423195 +10454 51.6311722356 0.1970855786 +10455 51.6339125508 0.2003940193 +10456 51.6368499633 0.2032325359 +10457 51.6399533706 0.2055709798 +10458 51.6431899062 0.2073844812 +10459 51.6465252864 0.2086537166 +10460 51.6499241731 0.2093651178 +10461 51.6533505473 0.2095110204 +10462 51.6567680908 0.2090897501 +10463 51.6601405706 0.2081056462 +10464 51.6634322239 0.2065690208 +10465 51.6666081371 0.2044960546 +10466 51.6696346173 0.2019086297 +10467 51.6724795505 0.1988341018 +10468 51.6751127429 0.1953050134 +10469 51.6775062434 0.1913587504 +10470 51.6796346408 0.1870371475 +10471 51.681475335 0.1823860437 +10472 51.6830087786 0.1774547962 +10473 51.684218685 0.172295754 +10474 51.6850922028 0.1669637005 +10475 51.685620053 0.161515268 +10476 51.6857966284 0.1560083333 +10477 51.6095305556 0.114975 +10478 51.6232006389 0.1306218889 +10479 51.6247434871 0.1264803317 +10480 51.6265123207 0.1225788083 +10481 51.62849275 0.1189490556 +10482 51.61475 0.1032222222 +10483 51.6095305556 0.114975 +10484 51.6945361111 0.1946944444 +10485 51.6821273889 0.1804416944 +10486 51.6806366835 0.1846372067 +10487 51.6789167892 0.1885991606 +10488 51.67698175 0.1922952778 +10489 51.6893194444 0.2064694444 +10490 51.6945361111 0.1946944444 +10491 51.6093166667 0.1154222222 +10492 51.623036 0.1311190278 +10493 51.6245517675 0.126951311 +10494 51.6262951166 0.1230198351 +10495 51.6282518611 0.1193565833 +10496 51.6145361111 0.1036666667 +10497 51.6093166667 0.1154222222 +10498 51.6943527778 0.1951388889 +10499 51.6819718056 0.1809234167 +10500 51.6804547511 0.1850942614 +10501 51.678710016 0.1890278444 +10502 51.6767518333 0.1926921111 +10503 51.6891361111 0.2069138889 +10504 51.6943527778 0.1951388889 +10505 51.9266121564 0.235 +10506 51.9264344831 0.2287898076 +10507 51.9259029834 0.2226327443 +10508 51.9250222041 0.2165814812 +10509 51.9237996799 0.2106877765 +10510 51.9222458679 0.2050020304 +10511 51.920374058 0.1995728501 +10512 51.9182002582 0.1944466326 +10513 51.9157430564 0.1896671656 +10514 51.9130234609 0.1852752525 +10515 51.9100647192 0.1813083633 +10516 51.9068921185 0.1778003149 +10517 51.9035327683 0.1747809834 +10518 51.9000153673 0.1722760514 +10519 51.896369958 0.1703067912 +10520 51.8926276688 0.1688898867 +10521 51.8888204475 0.1680372953 +10522 51.8849807881 0.1677561503 +10523 51.8811414532 0.1680487046 +10524 51.8773351946 0.1689123167 +10525 51.8735944735 0.1703394781 +10526 51.8699511843 0.1723178822 +10527 51.8664363832 0.1748305335 +10528 51.863080024 0.1778558969 +10529 51.8599107037 0.1813680845 +10530 51.8569554202 0.1853370792 +10531 51.8542393427 0.1897289923 +10532 51.851785599 0.1945063538 +10533 51.8496150796 0.1996284322 +10534 51.8477462608 0.2050515805 +10535 51.8461950486 0.2107296074 +10536 51.8449746444 0.2166141682 +10537 51.8440954332 0.2226551744 +10538 51.8435648963 0.2288012169 +10539 51.8433875477 0.235 +10540 51.8435648963 0.2411987831 +10541 51.8440954332 0.2473448256 +10542 51.8449746444 0.2533858318 +10543 51.8461950486 0.2592703926 +10544 51.8477462608 0.2649484195 +10545 51.8496150796 0.2703715678 +10546 51.851785599 0.2754936462 +10547 51.8542393427 0.2802710077 +10548 51.8569554202 0.2846629208 +10549 51.8599107037 0.2886319155 +10550 51.863080024 0.2921441031 +10551 51.8664363832 0.2951694665 +10552 51.8699511843 0.2976821178 +10553 51.8735944735 0.2996605219 +10554 51.8773351946 0.3010876833 +10555 51.8811414532 0.3019512954 +10556 51.8849807881 0.3022438497 +10557 51.8888204475 0.3019627047 +10558 51.8926276688 0.3011101133 +10559 51.896369958 0.2996932088 +10560 51.9000153673 0.2977239486 +10561 51.9035327683 0.2952190166 +10562 51.9068921185 0.2921996851 +10563 51.9100647192 0.2886916367 +10564 51.9130234609 0.2847247475 +10565 51.9157430564 0.2803328344 +10566 51.9182002582 0.2755533674 +10567 51.920374058 0.2704271499 +10568 51.9222458679 0.2649979696 +10569 51.9237996799 0.2593122235 +10570 51.9250222041 0.2534185188 +10571 51.9259029834 0.2473672557 +10572 51.9264344831 0.2412101924 +10573 51.9266121564 0.235 +10574 51.8410361111 0.1788194444 +10575 51.8516743056 0.1947456944 +10576 51.8535562167 0.1909710506 +10577 51.8556015888 0.187424914 +10578 51.8577998056 0.1841257222 +10579 51.8471527778 0.1681888889 +10580 51.8410361111 0.1788194444 +10581 51.9311305556 0.2941833333 +10582 51.9184224444 0.2750736667 +10583 51.916548197 0.2788639154 +10584 51.9145097839 0.2824255347 +10585 51.9123178333 0.28574 +10586 51.9250166667 0.3048388889 +10587 51.9311305556 0.2941833333 +10588 51.9282896919 0.4491666667 +10589 51.9281131227 0.4436301033 +10590 51.927585291 0.4381523581 +10591 51.926711804 0.4327916201 +10592 51.9255019406 0.4276048275 +10593 51.9239685519 0.422647059 +10594 51.922127924 0.417970946 +10595 51.9199996043 0.4136261113 +10596 51.9176061921 0.4096586409 +10597 51.9149730981 0.4061105941 +10598 51.9121282729 0.4030195576 +10599 51.9091019091 0.4004182481 +10600 51.90592612 0.3983341674 +10601 51.9026345974 0.3967893144 +10602 51.8992622536 0.3957999552 +10603 51.8958448503 0.3953764561 +10604 51.8924186188 0.395523178 +10605 51.889019876 0.3962384364 +10606 51.885684639 0.3975145241 +10607 51.8824482445 0.3993377987 +10608 51.8793449744 0.4016888316 +10609 51.8764076934 0.4045426185 +10610 51.8736675024 0.4078688481 +10611 51.87115341 0.4116322255 +10612 51.8688920266 0.4157928483 +10613 51.866907284 0.4203066295 +10614 51.8652201834 0.4251257647 +10615 51.8638485746 0.4301992364 +10616 51.8628069678 0.4354733526 +10617 51.8621063813 0.4408923117 +10618 51.8617542257 0.4463987898 +10619 51.8617542257 0.4519345435 +10620 51.8621063813 0.4574410216 +10621 51.8628069678 0.4628599807 +10622 51.8638485746 0.4681340969 +10623 51.8652201834 0.4732075687 +10624 51.866907284 0.4780267038 +10625 51.8688920266 0.4825404851 +10626 51.87115341 0.4867011078 +10627 51.8736675024 0.4904644852 +10628 51.8764076934 0.4937907148 +10629 51.8793449744 0.4966445018 +10630 51.8824482445 0.4989955347 +10631 51.885684639 0.5008188092 +10632 51.889019876 0.502094897 +10633 51.8924186188 0.5028101553 +10634 51.8958448503 0.5029568773 +10635 51.8992622536 0.5025333781 +10636 51.9026345974 0.5015440189 +10637 51.90592612 0.4999991659 +10638 51.9091019091 0.4979150853 +10639 51.9121282729 0.4953137757 +10640 51.9149730981 0.4922227392 +10641 51.9176061921 0.4886746924 +10642 51.9199996043 0.484707222 +10643 51.922127924 0.4803623874 +10644 51.9239685519 0.4756862743 +10645 51.9255019406 0.4707285058 +10646 51.926711804 0.4655417132 +10647 51.927585291 0.4601809752 +10648 51.9281131227 0.45470323 +10649 51.9282896919 0.4491666667 +10650 51.8864027778 0.3730888889 +10651 51.88766425 0.3966865556 +10652 51.8906213139 0.3958296993 +10653 51.8936141315 0.3954070986 +10654 51.8966183333 0.3954222778 +10655 51.8953583333 0.3718527778 +10656 51.8864027778 0.3730888889 +10657 51.9035638889 0.5269916667 +10658 51.9022398056 0.5016900556 +10659 51.8992807816 0.5025295237 +10660 51.8962869854 0.502934256 +10661 51.8932828056 0.5029010556 +10662 51.8946083333 0.5282305556 +10663 51.9035638889 0.5269916667 +10664 51.8861333333 0.3729722222 +10665 51.8873999167 0.3967850556 +10666 51.8903525916 0.3958892902 +10667 51.8933432088 0.3954272954 +10668 51.8963474167 0.3954029167 +10669 51.8950888889 0.3717416667 +10670 51.8861333333 0.3729722222 +10671 51.9032611111 0.5270416667 +10672 51.9019466389 0.50179325 +10673 51.8989830515 0.502589532 +10674 51.8959871214 0.5029506279 +10675 51.89298325 0.5028736667 +10676 51.8943055556 0.5282722222 +10677 51.9032611111 0.5270416667 +10678 51.3851566777 0.5028888889 +10679 51.3849800946 0.4974181135 +10680 51.3844522212 0.4920054548 +10681 51.383578665 0.4867084083 +10682 51.3823687051 0.4815832334 +10683 51.3808351933 0.4766843526 +10684 51.3789944163 0.4720637708 +10685 51.3768659223 0.4677705203 +10686 51.3744723119 0.4638501396 +10687 51.3718389969 0.4603441886 +10688 51.3689939296 0.4572898085 +10689 51.3659673044 0.4547193289 +10690 51.3627912369 0.4526599272 +10691 51.3594994211 0.4511333435 +10692 51.3561267721 0.4501556536 +10693 51.3527090546 0.4497371038 +10694 51.349282503 0.4498820067 +10695 51.3458834377 0.4505887009 +10696 51.3425478795 0.4518495739 +10697 51.3393111687 0.4536511481 +10698 51.336207591 0.4559742282 +10699 51.3332700152 0.4587941086 +10700 51.3305295459 0.4620808394 +10701 51.3280151953 0.4657995454 +10702 51.3257535772 0.4699107981 +10703 51.3237686269 0.4743710333 +10704 51.3220813485 0.4791330129 +10705 51.3207095942 0.4841463232 +10706 51.3196678763 0.4893579072 +10707 51.3189672149 0.4947126228 +10708 51.3186150215 0.5001538236 +10709 51.3186150215 0.5056239542 +10710 51.3189672149 0.511065155 +10711 51.3196678763 0.5164198706 +10712 51.3207095942 0.5216314546 +10713 51.3220813485 0.5266447649 +10714 51.3237686269 0.5314067444 +10715 51.3257535772 0.5358669797 +10716 51.3280151953 0.5399782323 +10717 51.3305295459 0.5436969384 +10718 51.3332700152 0.5469836691 +10719 51.336207591 0.5498035496 +10720 51.3393111687 0.5521266296 +10721 51.3425478795 0.5539282038 +10722 51.3458834377 0.5551890769 +10723 51.349282503 0.5558957711 +10724 51.3527090546 0.5560406739 +10725 51.3561267721 0.5556221241 +10726 51.3594994211 0.5546444343 +10727 51.3627912369 0.5531178505 +10728 51.3659673044 0.5510584489 +10729 51.3689939296 0.5484879693 +10730 51.3718389969 0.5454335892 +10731 51.3744723119 0.5419276382 +10732 51.3768659223 0.5380072574 +10733 51.3789944163 0.533714007 +10734 51.3808351933 0.5290934252 +10735 51.3823687051 0.5241945444 +10736 51.383578665 0.5190693695 +10737 51.3844522212 0.5137723229 +10738 51.3849800946 0.5083596643 +10739 51.3851566777 0.5028888889 +10740 51.3058194444 0.4834861111 +10741 51.3192941389 0.4918709444 +10742 51.320048953 0.4872282527 +10743 51.321062879 0.4827129256 +10744 51.3223276667 0.4783616944 +10745 51.3090888889 0.4701277778 +10746 51.3058194444 0.4834861111 +10747 51.3997527778 0.5266194444 +10748 51.384 0.51678675 +10749 51.3830840819 0.5213616864 +10750 51.381913545 0.5257857541 +10751 51.3804979444 0.5300228333 +10752 51.3964833333 0.5400055556 +10753 51.3997527778 0.5266194444 +10754 51.3053888889 0.4839722222 +10755 51.3192133056 0.4924984444 +10756 51.3199332926 0.4878400458 +10757 51.3209135101 0.4833041184 +10758 51.3221459722 0.4789275833 +10759 51.3086333333 0.4705972222 +10760 51.3053888889 0.4839722222 +10761 51.3983277778 0.5259916667 +10762 51.3839471944 0.5170946389 +10763 51.3830139545 0.5216613468 +10764 51.381826592 0.5260746936 +10765 51.3803948056 0.5302986389 +10766 51.3950861111 0.5393916667 +10767 51.3983277778 0.5259916667 +10768 51.1896827956 0.6444444444 +10769 51.1895062075 0.6389968451 +10770 51.188978319 0.6336071153 +10771 51.1881047377 0.6283325063 +10772 51.1868947429 0.6232290383 +10773 51.1853611865 0.6183509028 +10774 51.1835203555 0.6137498838 +10775 51.1813917985 0.6094748059 +10776 51.1789981163 0.6055710142 +10777 51.1763647214 0.6020798931 +10778 51.1735195665 0.5990384267 +10779 51.1704928469 0.5964788084 +10780 51.1673166787 0.5944281011 +10781 51.164024757 0.5929079536 +10782 51.1606519978 0.591934375 +10783 51.1572341668 0.5915175691 +10784 51.1538074997 0.5916618315 +10785 51.150408318 0.5923655089 +10786 51.1470726439 0.5936210222 +10787 51.1438358191 0.5954149519 +10788 51.1407321305 0.5977281846 +10789 51.1377944485 0.6005361204 +10790 51.1350538788 0.6038089363 +10791 51.1325394351 0.6075119051 +10792 51.1302777326 0.6116057653 +10793 51.1282927074 0.6160471368 +10794 51.1266053649 0.6207889809 +10795 51.1252335582 0.6257810969 +10796 51.1241918004 0.6309706512 +10797 51.123491112 0.6363027343 +10798 51.123138905 0.6417209384 +10799 51.123138905 0.6471679504 +10800 51.123491112 0.6525861545 +10801 51.1241918004 0.6579182377 +10802 51.1252335582 0.663107792 +10803 51.1266053649 0.668099908 +10804 51.1282927074 0.6728417521 +10805 51.1302777326 0.6772831236 +10806 51.1325394351 0.6813769837 +10807 51.1350538788 0.6850799526 +10808 51.1377944485 0.6883527685 +10809 51.1407321305 0.6911607043 +10810 51.1438358191 0.693473937 +10811 51.1470726439 0.6952678667 +10812 51.150408318 0.69652338 +10813 51.1538074997 0.6972270574 +10814 51.1572341668 0.6973713198 +10815 51.1606519978 0.6969545139 +10816 51.164024757 0.6959809353 +10817 51.1673166787 0.6944607878 +10818 51.1704928469 0.6924100805 +10819 51.1735195665 0.6898504622 +10820 51.1763647214 0.6868089958 +10821 51.1789981163 0.6833178747 +10822 51.1813917985 0.679414083 +10823 51.1835203555 0.6751390051 +10824 51.1853611865 0.6705379861 +10825 51.1868947429 0.6656598506 +10826 51.1881047377 0.6605563826 +10827 51.188978319 0.6552817736 +10828 51.1895062075 0.6498920438 +10829 51.1896827956 0.6444444444 +10830 51.1645833333 0.5663138889 +10831 51.1603403333 0.5918729444 +10832 51.1633046336 0.5926518716 +10833 51.1662126983 0.5938527671 +10834 51.1690408333 0.5954659167 +10835 51.1732722222 0.5699777778 +10836 51.1645833333 0.5663138889 +10837 51.1479583333 0.7218944444 +10838 51.1521301944 0.6969505833 +10839 51.1491710648 0.6961247654 +10840 51.1462707894 0.6948783343 +10841 51.1434529722 0.6932215 +10842 51.1392694444 0.7182361111 +10843 51.1479583333 0.7218944444 +10844 51.9477340257 0.6825 +10845 51.947557457 0.6769610427 +10846 51.9470296268 0.6714809291 +10847 51.9461561423 0.6661178735 +10848 51.9449462823 0.6609288387 +10849 51.943412898 0.6559689273 +10850 51.9415722755 0.6512907936 +10851 51.9394439619 0.6469440818 +10852 51.9370505568 0.6429748979 +10853 51.9344174707 0.6394253193 +10854 51.9315726541 0.636332949 +10855 51.9285462996 0.6337305176 +10856 51.9253705205 0.631645539 +10857 51.9220790084 0.6301000212 +10858 51.9187066755 0.6291102374 +10859 51.9152892834 0.6286865582 +10860 51.9118630633 0.6288333463 +10861 51.908464332 0.6295489163 +10862 51.9051291065 0.6308255577 +10863 51.9018927233 0.632649622 +10864 51.8987894642 0.635001672 +10865 51.8958521937 0.6378566928 +10866 51.8931120127 0.6411843597 +10867 51.8905979296 0.6449493626 +10868 51.8883365545 0.6491117818 +10869 51.8863518193 0.6536275115 +10870 51.8846647251 0.6584487265 +10871 51.8832931215 0.6635243874 +10872 51.8822515187 0.668800779 +10873 51.8815509349 0.6742220758 +10874 51.8811987806 0.6797309292 +10875 51.8811987806 0.6852690708 +10876 51.8815509349 0.6907779242 +10877 51.8822515187 0.696199221 +10878 51.8832931215 0.7014756126 +10879 51.8846647251 0.7065512735 +10880 51.8863518193 0.7113724885 +10881 51.8883365545 0.7158882182 +10882 51.8905979296 0.7200506374 +10883 51.8931120127 0.7238156403 +10884 51.8958521937 0.7271433072 +10885 51.8987894642 0.729998328 +10886 51.9018927233 0.732350378 +10887 51.9051291065 0.7341744423 +10888 51.908464332 0.7354510837 +10889 51.9118630633 0.7361666537 +10890 51.9152892834 0.7363134418 +10891 51.9187066755 0.7358897626 +10892 51.9220790084 0.7348999788 +10893 51.9253705205 0.733354461 +10894 51.9285462996 0.7312694824 +10895 51.9315726541 0.728667051 +10896 51.9344174707 0.7255746807 +10897 51.9370505568 0.7220251021 +10898 51.9394439619 0.7180559182 +10899 51.9415722755 0.7137092064 +10900 51.943412898 0.7090310727 +10901 51.9449462823 0.7040711613 +10902 51.9461561423 0.6988821265 +10903 51.9470296268 0.6935190709 +10904 51.947557457 0.6880389573 +10905 51.9477340257 0.6825 +10906 51.8858888889 0.6188194444 +10907 51.8936288333 0.6405008056 +10908 51.8960555344 0.6376370069 +10909 51.8986320512 0.6351382452 +10910 51.9013374167 0.6330249167 +10911 51.8936777778 0.6115694444 +10912 51.8858888889 0.6188194444 +10913 51.942025 0.7473027778 +10914 51.9343375 0.7256713333 +10915 51.9318493242 0.7283957123 +10916 51.9292193892 0.7307458014 +10917 51.9264691389 0.7327025 +10918 51.9342361111 0.7545583333 +10919 51.942025 0.7473027778 +10920 51.6118921753 0.6933333333 +10921 51.6117144943 0.6871661804 +10922 51.6111829714 0.6810517867 +10923 51.6103021536 0.6750424567 +10924 51.6090795755 0.6691895887 +10925 51.6075256945 0.6635432321 +10926 51.6056538008 0.6581516565 +10927 51.6034799024 0.6530609364 +10928 51.6010225879 0.648314556 +10929 51.5983028658 0.6439530358 +10930 51.5953439844 0.6400135864 +10931 51.5921712314 0.6365297913 +10932 51.5888117171 0.6335313205 +10933 51.5852941413 0.63104368 +10934 51.5816485477 0.6290879964 +10935 51.5779060657 0.62768084 +10936 51.5740986447 0.6268340873 +10937 51.5702587803 0.6265548244 +10938 51.5664192368 0.6268452906 +10939 51.5626127676 0.627702865 +10940 51.5588718361 0.6291200932 +10941 51.5552283386 0.6310847554 +10942 51.5517133334 0.6335799758 +10943 51.5483567765 0.6365843696 +10944 51.5451872669 0.6400722293 +10945 51.5422318046 0.644013746 +10946 51.5395155609 0.6483752663 +10947 51.5370616655 0.6531195793 +10948 51.5348910106 0.6582062349 +10949 51.5330220742 0.6635918876 +10950 51.5314707638 0.6692306642 +10951 51.5302502819 0.6750745535 +10952 51.5293710145 0.6810738118 +10953 51.5288404435 0.6871773836 +10954 51.5286630835 0.6933333333 +10955 51.5288404435 0.699489283 +10956 51.5293710145 0.7055928549 +10957 51.5302502819 0.7115921131 +10958 51.5314707638 0.7174360024 +10959 51.5330220742 0.7230747791 +10960 51.5348910106 0.7284604317 +10961 51.5370616655 0.7335470874 +10962 51.5395155609 0.7382914004 +10963 51.5422318046 0.7426529206 +10964 51.5451872669 0.7465944374 +10965 51.5483567765 0.750082297 +10966 51.5517133334 0.7530866908 +10967 51.5552283386 0.7555819112 +10968 51.5588718361 0.7575465735 +10969 51.5626127676 0.7589638016 +10970 51.5664192368 0.7598213761 +10971 51.5702587803 0.7601118423 +10972 51.5740986447 0.7598325793 +10973 51.5779060657 0.7589858267 +10974 51.5816485477 0.7575786702 +10975 51.5852941413 0.7556229866 +10976 51.5888117171 0.7531353462 +10977 51.5921712314 0.7501368754 +10978 51.5953439844 0.7466530802 +10979 51.5983028658 0.7427136309 +10980 51.6010225879 0.7383521107 +10981 51.6034799024 0.7336057302 +10982 51.6056538008 0.7285150102 +10983 51.6075256945 0.7231234345 +10984 51.6090795755 0.7174770779 +10985 51.6103021536 0.7116242099 +10986 51.6111829714 0.7056148799 +10987 51.6117144943 0.6995004863 +10988 51.6118921753 0.6933333333 +10989 51.5359555556 0.6291166667 +10990 51.5424989444 0.6436260556 +10991 51.544803412 0.6405434667 +10992 51.5472403342 0.637734927 +10993 51.5497970556 0.6352150556 +10994 51.5432416667 0.6206805556 +10995 51.5359555556 0.6291166667 +10996 51.6042944444 0.7563638889 +10997 51.5982206389 0.7428335 +10998 51.5959248333 0.7459369184 +10999 51.5934956228 0.7487662855 +11000 51.5909456667 0.7513069167 +11001 51.5970083333 0.7648138889 +11002 51.6042944444 0.7563638889 +11003 51.50322267 -0.1795388889 +11004 51.5030460899 -0.1850237897 +11005 51.5025182256 -0.1904504231 +11006 51.5016446845 -0.1957611449 +11007 51.5004347457 -0.2008995498 +11008 51.4989012607 -0.2058110744 +11009 51.4970605163 -0.2104435795 +11010 51.4949320603 -0.2147479056 +11011 51.4925384931 -0.2186783971 +11012 51.4899052263 -0.2221933866 +11013 51.4870602117 -0.2252556374 +11014 51.4840336435 -0.2278327366 +11015 51.4808576366 -0.2298974372 +11016 51.4775658847 -0.2314279437 +11017 51.4741933023 -0.2324081392 +11018 51.4707756531 -0.2328277518 +11019 51.4673491713 -0.2326824584 +11020 51.4639501761 -0.2319739255 +11021 51.4606146879 -0.2307097858 +11022 51.4573780459 -0.2289035523 +11023 51.4542745352 -0.2265744705 +11024 51.4513370235 -0.22374731 +11025 51.4485966148 -0.2204520984 +11026 51.4460823203 -0.2167238008 +11027 51.4438207533 -0.2126019478 +11028 51.4418358481 -0.2081302155 +11029 51.4401486084 -0.2033559639 +11030 51.4387768857 -0.1983297361 +11031 51.437735192 -0.1931047256 +11032 51.4370345469 -0.187736216 +11033 51.4366823617 -0.1822809993 +11034 51.4366823617 -0.1767967785 +11035 51.4370345469 -0.1713415617 +11036 51.437735192 -0.1659730521 +11037 51.4387768857 -0.1607480417 +11038 51.4401486084 -0.1557218139 +11039 51.4418358481 -0.1509475623 +11040 51.4438207533 -0.14647583 +11041 51.4460823203 -0.142353977 +11042 51.4485966148 -0.1386256794 +11043 51.4513370235 -0.1353304678 +11044 51.4542745352 -0.1325033072 +11045 51.4573780459 -0.1301742255 +11046 51.4606146879 -0.128367992 +11047 51.4639501761 -0.1271038523 +11048 51.4673491713 -0.1263953194 +11049 51.4707756531 -0.126250026 +11050 51.4741933023 -0.1266696386 +11051 51.4775658847 -0.1276498341 +11052 51.4808576366 -0.1291803406 +11053 51.4840336435 -0.1312450412 +11054 51.4870602117 -0.1338221404 +11055 51.4899052263 -0.1368843911 +11056 51.4925384931 -0.1403993807 +11057 51.4949320603 -0.1443298721 +11058 51.4970605163 -0.1486341983 +11059 51.4989012607 -0.1532667033 +11060 51.5004347457 -0.158178228 +11061 51.5016446845 -0.1633166329 +11062 51.5025182256 -0.1686273547 +11063 51.5030460899 -0.1740539881 +11064 51.50322267 -0.1795388889 +11065 51.3392541623 -0.0934361111 +11066 51.339077578 -0.0989014207 +11067 51.3385497011 -0.1043086718 +11068 51.337676139 -0.1096004267 +11069 51.3364661709 -0.1147204823 +11070 51.3349326486 -0.1196144705 +11071 51.333091859 -0.1242304386 +11072 51.3309633502 -0.1285194033 +11073 51.3285697229 -0.1324358716 +11074 51.3259363892 -0.1359383252 +11075 51.3230913013 -0.1389896597 +11076 51.320064654 -0.1415575778 +11077 51.3168885628 -0.143614929 +11078 51.3135967222 -0.1451399949 +11079 51.3102240474 -0.1461167151 +11080 51.3068063032 -0.1465348537 +11081 51.3033797245 -0.1463901019 +11082 51.2999806319 -0.1456841192 +11083 51.2966450465 -0.1444245102 +11084 51.2934083089 -0.1426247389 +11085 51.2903047052 -0.1403039812 +11086 51.2873671045 -0.1374869178 +11087 51.2846266116 -0.1342034687 +11088 51.2821122391 -0.1304884741 +11089 51.2798506013 -0.1263813233 +11090 51.2778656334 -0.1219255368 +11091 51.2761783399 -0.117168306 +11092 51.2748065733 -0.1121599941 +11093 51.273764846 -0.1069536056 +11094 51.2730641783 -0.1016042276 +11095 51.2727119817 -0.0961684503 +11096 51.2727119817 -0.090703772 +11097 51.2730641783 -0.0852679946 +11098 51.273764846 -0.0799186166 +11099 51.2748065733 -0.0747122281 +11100 51.2761783399 -0.0697039163 +11101 51.2778656334 -0.0649466854 +11102 51.2798506013 -0.060490899 +11103 51.2821122391 -0.0563837481 +11104 51.2846266116 -0.0526687535 +11105 51.2873671045 -0.0493853045 +11106 51.2903047052 -0.046568241 +11107 51.2934083089 -0.0442474834 +11108 51.2966450465 -0.0424477121 +11109 51.2999806319 -0.0411881031 +11110 51.3033797245 -0.0404821204 +11111 51.3068063032 -0.0403373686 +11112 51.3102240474 -0.0407555071 +11113 51.3135967222 -0.0417322274 +11114 51.3168885628 -0.0432572932 +11115 51.320064654 -0.0453146444 +11116 51.3230913013 -0.0478825625 +11117 51.3259363892 -0.050933897 +11118 51.3285697229 -0.0544363506 +11119 51.3309633502 -0.058352819 +11120 51.333091859 -0.0626417836 +11121 51.3349326486 -0.0672577518 +11122 51.3364661709 -0.07215174 +11123 51.337676139 -0.0772717955 +11124 51.3385497011 -0.0825635504 +11125 51.339077578 -0.0879708015 +11126 51.3392541623 -0.0934361111 +11127 51.3194987197 -1.7810361111 +11128 51.3193221349 -1.7864990728 +11129 51.3187942564 -1.791904001 +11130 51.3179206918 -1.7971934828 +11131 51.3167107202 -1.8023113392 +11132 51.3151771934 -1.8072032258 +11133 51.3133363983 -1.8118172121 +11134 51.3112078832 -1.8161043357 +11135 51.3088142487 -1.8200191235 +11136 51.3061809068 -1.8235200746 +11137 51.3033358101 -1.8265701009 +11138 51.3003091533 -1.8291369187 +11139 51.2971330519 -1.8311933891 +11140 51.2938412006 -1.8327178029 +11141 51.2904685147 -1.8336941066 +11142 51.287050759 -1.8341120685 +11143 51.2836241687 -1.8339673816 +11144 51.2802250642 -1.8332617045 +11145 51.2768894671 -1.8320026385 +11146 51.2736527181 -1.8302036416 +11147 51.2705491032 -1.8278838816 +11148 51.2676114917 -1.8250680283 +11149 51.2648709887 -1.8217859889 +11150 51.2623566068 -1.8180725886 +11151 51.2600949604 -1.8139671997 +11152 51.2581099849 -1.8095133244 +11153 51.256422685 -1.8047581334 +11154 51.255050913 -1.7997519687 +11155 51.2540091818 -1.7945478119 +11156 51.2533085113 -1.7892007268 +11157 51.2529563133 -1.7837672792 +11158 51.2529563133 -1.778304943 +11159 51.2533085113 -1.7728714954 +11160 51.2540091818 -1.7675244103 +11161 51.255050913 -1.7623202535 +11162 51.256422685 -1.7573140888 +11163 51.2581099849 -1.7525588979 +11164 51.2600949604 -1.7481050225 +11165 51.2623566068 -1.7439996337 +11166 51.2648709887 -1.7402862334 +11167 51.2676114917 -1.737004194 +11168 51.2705491032 -1.7341883406 +11169 51.2736527181 -1.7318685806 +11170 51.2768894671 -1.7300695837 +11171 51.2802250642 -1.7288105177 +11172 51.2836241687 -1.7281048407 +11173 51.287050759 -1.7279601537 +11174 51.2904685147 -1.7283781156 +11175 51.2938412006 -1.7293544194 +11176 51.2971330519 -1.7308788332 +11177 51.3003091533 -1.7329353036 +11178 51.3033358101 -1.7355021213 +11179 51.3061809068 -1.7385521476 +11180 51.3088142487 -1.7420530988 +11181 51.3112078832 -1.7459678865 +11182 51.3133363983 -1.7502550102 +11183 51.3151771934 -1.7548689964 +11184 51.3167107202 -1.759760883 +11185 51.3179206918 -1.7648787395 +11186 51.3187942564 -1.7701682212 +11187 51.3193221349 -1.7755731495 +11188 51.3194987197 -1.7810361111 +11189 51.9124147822 -1.217775 +11190 51.9122382126 -1.2233096109 +11191 51.9117103797 -1.2287854244 +11192 51.9108368907 -1.2341442722 +11193 51.9096270245 -1.2393292361 +11194 51.9080936322 -1.2442852569 +11195 51.906253 -1.2489597219 +11196 51.9041246752 -1.2533030257 +11197 51.9017312573 -1.2572690985 +11198 51.8990981568 -1.260815896 +11199 51.8962533245 -1.2639058446 +11200 51.8932269531 -1.2665062392 +11201 51.8900511559 -1.2685895874 +11202 51.8867596248 -1.2701338983 +11203 51.8833872721 -1.2711229111 +11204 51.8799698596 -1.2715462634 +11205 51.8765436188 -1.2713995955 +11206 51.8731448665 -1.2706845913 +11207 51.8698096202 -1.2694089551 +11208 51.8665732165 -1.2675863246 +11209 51.8634699373 -1.2652361213 +11210 51.8605326478 -1.2623833407 +11211 51.8577924487 -1.2590582833 +11212 51.8552783487 -1.2552962317 +11213 51.8530169585 -1.2511370741 +11214 51.8510322098 -1.246624882 +11215 51.849345104 -1.2418074431 +11216 51.8479734909 -1.2367357568 +11217 51.8469318809 -1.2314634964 +11218 51.8462312922 -1.2260464439 +11219 51.8458791355 -1.2205419031 +11220 51.8458791355 -1.2150080969 +11221 51.8462312922 -1.2095035561 +11222 51.8469318809 -1.2040865036 +11223 51.8479734909 -1.1988142432 +11224 51.849345104 -1.1937425569 +11225 51.8510322098 -1.188925118 +11226 51.8530169585 -1.1844129259 +11227 51.8552783487 -1.1802537683 +11228 51.8577924487 -1.1764917167 +11229 51.8605326478 -1.1731666593 +11230 51.8634699373 -1.1703138787 +11231 51.8665732165 -1.1679636754 +11232 51.8698096202 -1.1661410449 +11233 51.8731448665 -1.1648654087 +11234 51.8765436188 -1.1641504045 +11235 51.8799698596 -1.1640037366 +11236 51.8833872721 -1.1644270889 +11237 51.8867596248 -1.1654161017 +11238 51.8900511559 -1.1669604126 +11239 51.8932269531 -1.1690437608 +11240 51.8962533245 -1.1716441554 +11241 51.8990981568 -1.174734104 +11242 51.9017312573 -1.1782809015 +11243 51.9041246752 -1.1822469743 +11244 51.906253 -1.1865902781 +11245 51.9080936322 -1.1912647431 +11246 51.9096270245 -1.1962207639 +11247 51.9108368907 -1.2014057278 +11248 51.9117103797 -1.2067645756 +11249 51.9122382126 -1.2122403891 +11250 51.9124147822 -1.217775 +11251 51.9003787396 -1.6941888889 +11252 51.9002021697 -1.6997220206 +11253 51.8996743359 -1.7051963708 +11254 51.8988008453 -1.7105537866 +11255 51.897590977 -1.7157373652 +11256 51.8960575819 -1.720692062 +11257 51.8942169465 -1.7253652785 +11258 51.8920886178 -1.7297074225 +11259 51.8896951955 -1.7336724366 +11260 51.8870620902 -1.7372182877 +11261 51.8842172525 -1.7403074122 +11262 51.8811908754 -1.7429071136 +11263 51.878015072 -1.744989907 +11264 51.8747235344 -1.7465338071 +11265 51.871351175 -1.7475225576 +11266 51.8679337555 -1.7479457987 +11267 51.8645075076 -1.7477991716 +11268 51.8611087482 -1.74708436 +11269 51.8577734948 -1.7458090659 +11270 51.8545370841 -1.7439869233 +11271 51.8514337981 -1.7416373485 +11272 51.848496502 -1.7387853301 +11273 51.8457562968 -1.7354611608 +11274 51.8432421911 -1.7317001135 +11275 51.8409807957 -1.7275420659 +11276 51.8389960424 -1.7230310777 +11277 51.8373089327 -1.7182149238 +11278 51.8359373164 -1.7131445901 +11279 51.8348957039 -1.7078737356 +11280 51.8341951135 -1.7024581275 +11281 51.8338429559 -1.6969550543 +11282 51.8338429559 -1.6914227235 +11283 51.8341951135 -1.6859196503 +11284 51.8348957039 -1.6805040421 +11285 51.8359373164 -1.6752331877 +11286 51.8373089327 -1.670162854 +11287 51.8389960424 -1.6653467001 +11288 51.8409807957 -1.6608357118 +11289 51.8432421911 -1.6566776643 +11290 51.8457562968 -1.6529166169 +11291 51.848496502 -1.6495924477 +11292 51.8514337981 -1.6467404293 +11293 51.8545370841 -1.6443908545 +11294 51.8577734948 -1.6425687119 +11295 51.8611087482 -1.6412934178 +11296 51.8645075076 -1.6405786061 +11297 51.8679337555 -1.6404319791 +11298 51.871351175 -1.6408552202 +11299 51.8747235344 -1.6418439707 +11300 51.878015072 -1.6433878708 +11301 51.8811908754 -1.6454706642 +11302 51.8842172525 -1.6480703656 +11303 51.8870620902 -1.6511594901 +11304 51.8896951955 -1.6547053411 +11305 51.8920886178 -1.6586703553 +11306 51.8942169465 -1.6630124993 +11307 51.8960575819 -1.6676857158 +11308 51.897590977 -1.6726404126 +11309 51.8988008453 -1.6778239912 +11310 51.8996743359 -1.6831814069 +11311 51.9002021697 -1.6886557571 +11312 51.9003787396 -1.6941888889 +11313 51.8243148333 -1.7391218333 +11314 51.8383616389 -1.7213525556 +11315 51.8399944628 -1.7254230493 +11316 51.8418478204 -1.7292396587 +11317 51.8439066389 -1.7327713333 +11318 51.8298625 -1.7505336944 +11319 51.8243148333 -1.7391218333 +11320 51.9098425278 -1.6491845278 +11321 51.89581225 -1.6669975556 +11322 51.8941777929 -1.6629237494 +11323 51.8923226558 -1.6591049889 +11324 51.8902619722 -1.6555723889 +11325 51.9042949167 -1.6377523889 +11326 51.9098425278 -1.6491845278 +11327 51.8591138056 -1.7725545278 +11328 51.8604959167 -1.7468936389 +11329 51.8634648455 -1.7476408861 +11330 51.8664633953 -1.7479527579 +11331 51.8694671389 -1.7478266389 +11332 51.8680682778 -1.7737993056 +11333 51.8591138056 -1.7725545278 +11334 51.8766028056 -1.6136181389 +11335 51.8751070833 -1.6419936111 +11336 51.8721608815 -1.641039975 +11337 51.869173453 -1.6405194626 +11338 51.8661691389 -1.64043625 +11339 51.8676483611 -1.6123731111 +11340 51.8766028056 -1.6136181389 +11341 51.8932725278 -1.7599274722 +11342 51.8831991667 -1.7412547778 +11343 51.8857675435 -1.738709554 +11344 51.8881829232 -1.735799195 +11345 51.8904255 -1.7325475278 +11346 51.9000425 -1.7503725833 +11347 51.8932725278 -1.7599274722 +11348 51.8354350556 -1.6308653333 +11349 51.84670925 -1.6516788333 +11350 51.8444133462 -1.6548287542 +11351 51.8423031413 -1.6583005968 +11352 51.8403958889 -1.6620659167 +11353 51.8286650278 -1.6404065278 +11354 51.8354350556 -1.6308653333 +11355 51.4865194444 -2.4396638889 +11356 51.485325 -2.4446388889 +11357 51.4817361111 -2.4478944444 +11358 51.4779722222 -2.4456416667 +11359 51.4765722222 -2.438575 +11360 51.4785194444 -2.4337638889 +11361 51.4811166667 -2.4321583333 +11362 51.4834777778 -2.4321638889 +11363 51.4854361111 -2.4338861111 +11364 51.4865194444 -2.4396638889 +11365 51.8272222222 -0.8018638889 +11366 51.8240194444 -0.8080638889 +11367 51.8205972222 -0.8083861111 +11368 51.8157416667 -0.8018833333 +11369 51.8176833333 -0.7922305556 +11370 51.8210444444 -0.7900166667 +11371 51.8265 -0.7949638889 +11372 51.8272222222 -0.8018638889 +11373 51.5032916667 0.0990305556 +11374 51.4976583333 0.0834944444 +11375 51.4909166667 0.0804333333 +11376 51.4882305556 0.0945611111 +11377 51.4915305556 0.097125 +11378 51.4949638889 0.1065527778 +11379 51.5032916667 0.0990305556 +11380 51.4857444444 -2.5945583333 +11381 51.4835722222 -2.5999805556 +11382 51.4800527778 -2.6006527778 +11383 51.4762111111 -2.5943277778 +11384 51.4770777778 -2.5866972222 +11385 51.4802305556 -2.5841138889 +11386 51.4824888889 -2.5845861111 +11387 51.4847722222 -2.5889111111 +11388 51.4857444444 -2.5945583333 +11389 51.4562194444 -0.1273222222 +11390 51.4538527778 -0.132775 +11391 51.4481638889 -0.132025 +11392 51.4472388889 -0.1223611111 +11393 51.4488194444 -0.1186333333 +11394 51.4525472222 -0.1174055556 +11395 51.4551111111 -0.1195583333 +11396 51.4562194444 -0.1273222222 +11397 51.4362277778 -0.4930166667 +11398 51.4301416667 -0.4903944444 +11399 51.4280722222 -0.4851722222 +11400 51.4289388889 -0.4792944444 +11401 51.4316027778 -0.4755583333 +11402 51.4384027778 -0.4780916667 +11403 51.4362277778 -0.4930166667 +11404 51.8536888889 -1.1007305556 +11405 51.8471805556 -1.1028972222 +11406 51.84375 -1.0980777778 +11407 51.8436166667 -1.0904388889 +11408 51.8468194444 -1.0851861111 +11409 51.8508305556 -1.0848166667 +11410 51.8538083333 -1.0891916667 +11411 51.8536888889 -1.1007305556 +11412 51.4860472222 -3.1672138889 +11413 51.4838527778 -3.1757305556 +11414 51.4788194444 -3.1752527778 +11415 51.475225 -3.1696805556 +11416 51.4761972222 -3.1643611111 +11417 51.4816305556 -3.1593388889 +11418 51.4860472222 -3.1672138889 +11419 51.7420111111 0.4828416667 +11420 51.7345722222 0.4758444444 +11421 51.7312444444 0.4857611111 +11422 51.7308777778 0.4934583333 +11423 51.7330944444 0.4965583333 +11424 51.7377777778 0.4958222222 +11425 51.7420111111 0.4828416667 +11426 51.3271333333 -0.6469388889 +11427 51.3213472222 -0.6526472222 +11428 51.3159916667 -0.6445972222 +11429 51.3213555556 -0.6323444444 +11430 51.3268527778 -0.6382083333 +11431 51.3271333333 -0.6469388889 +11432 51.34335 -0.1918888889 +11433 51.3409 -0.1973305556 +11434 51.3329555556 -0.1983277778 +11435 51.3300944444 -0.1936833333 +11436 51.3310472222 -0.1818777778 +11437 51.3386166667 -0.1805555556 +11438 51.3442861111 -0.1830305556 +11439 51.34335 -0.1918888889 +11440 51.2196083333 0.6149277778 +11441 51.2168722222 0.6088027778 +11442 51.2098166667 0.6115416667 +11443 51.213475 0.6257305556 +11444 51.2202638889 0.6254055556 +11445 51.2196083333 0.6149277778 +11446 51.6386305556 -2.4776472222 +11447 51.6297 -2.4745916667 +11448 51.6309111111 -2.4648611111 +11449 51.6342583333 -2.4564555556 +11450 51.6395611111 -2.4611111111 +11451 51.6397694444 -2.4666166667 +11452 51.6386305556 -2.4776472222 +11453 51.2906527778 -2.0452722222 +11454 51.2865527778 -2.0567666667 +11455 51.2805277778 -2.0523444444 +11456 51.2786583333 -2.0381527778 +11457 51.2842861111 -2.0346833333 +11458 51.2912138889 -2.0350694444 +11459 51.2906527778 -2.0452722222 +11460 51.4456916667 -0.4374555556 +11461 51.4440722222 -0.4445888889 +11462 51.4351611111 -0.4464194444 +11463 51.4329861111 -0.4298361111 +11464 51.4443638889 -0.4255777778 +11465 51.4456916667 -0.4374555556 +11466 51.8984361111 -1.0123694444 +11467 51.8922777778 -1.01375 +11468 51.8879388889 -1.0127555556 +11469 51.8861833333 -1.0036888889 +11470 51.8892388889 -0.9968944444 +11471 51.8942055556 -0.9969638889 +11472 51.8977416667 -1.0004833333 +11473 51.8984361111 -1.0123694444 +11474 51.5932361111 -1.0232222222 +11475 51.5845388889 -1.0283555556 +11476 51.5818694444 -1.0128361111 +11477 51.5910694444 -1.0091694444 +11478 51.5932361111 -1.0232222222 +11479 51.2857555556 0.5243527778 +11480 51.2800194444 0.5127555556 +11481 51.2726805556 0.5232944444 +11482 51.2783527778 0.5339416667 +11483 51.2857555556 0.5243527778 +11484 51.5352527778 -3.5678111111 +11485 51.5326472222 -3.5710222222 +11486 51.5257222222 -3.5698055556 +11487 51.5271083333 -3.5522638889 +11488 51.5363333333 -3.5535388889 +11489 51.5352527778 -3.5678111111 +11490 51.5488361111 -0.1238444444 +11491 51.5393944444 -0.1224222222 +11492 51.54205 -0.1066055556 +11493 51.5491972222 -0.1114833333 +11494 51.5494138889 -0.1164833333 +11495 51.5488361111 -0.1238444444 +11496 51.3738055556 0.4812666667 +11497 51.3603027778 0.4916833333 +11498 51.3601055556 0.4963916667 +11499 51.3629972222 0.5000972222 +11500 51.3670333333 0.5027888889 +11501 51.3742805556 0.4962694444 +11502 51.3738055556 0.4812666667 +11503 51.2797444444 -0.4953472222 +11504 51.2761944444 -0.4993222222 +11505 51.2721388889 -0.4980666667 +11506 51.2680138889 -0.4950305556 +11507 51.2694277778 -0.4824361111 +11508 51.2802666667 -0.4863444444 +11509 51.2797444444 -0.4953472222 +11510 51.3994277778 0.8475638889 +11511 51.3857027778 0.8404138889 +11512 51.3830972222 0.8501388889 +11513 51.3849972222 0.8572611111 +11514 51.3958083333 0.8634527778 +11515 51.3994277778 0.8475638889 +11516 51.6182055556 -3.9554083333 +11517 51.61305 -3.9566 +11518 51.6103583333 -3.9516 +11519 51.6129305556 -3.9402194444 +11520 51.6185388889 -3.9434361111 +11521 51.6196555556 -3.9486805556 +11522 51.6182055556 -3.9554083333 +11523 51.7313888889 -0.5418638889 +11524 51.7286388889 -0.5458194444 +11525 51.7256777778 -0.54795 +11526 51.7209111111 -0.5487111111 +11527 51.7203027778 -0.5369555556 +11528 51.7278194444 -0.5273166667 +11529 51.7318416667 -0.5353611111 +11530 51.7313888889 -0.5418638889 +11531 51.7049333333 -2.8964611111 +11532 51.7013416667 -2.909075 +11533 51.6940388889 -2.9031472222 +11534 51.6980722222 -2.8909361111 +11535 51.7049333333 -2.8964611111 +11536 51.4561361111 -0.1751111111 +11537 51.4539194444 -0.1822138889 +11538 51.4496 -0.1864583333 +11539 51.4432166667 -0.1783527778 +11540 51.4481388889 -0.1683916667 +11541 51.4561361111 -0.1751111111 +11542 51.0667638889 -1.3355916667 +11543 51.0584444444 -1.3336277778 +11544 51.0595305556 -1.3203583333 +11545 51.0652861111 -1.3214416667 +11546 51.0690611111 -1.3242 +11547 51.0667638889 -1.3355916667 +11548 51.5210527778 -0.2490222222 +11549 51.5157277778 -0.2482861111 +11550 51.51225 -0.245725 +11551 51.513125 -0.2311805556 +11552 51.5218972222 -0.2334805556 +11553 51.5210527778 -0.2490222222 +11554 52.1480051098 -4.5594166667 +11555 52.1478285462 -4.5649804396 +11556 52.1473007313 -4.5704851043 +11557 52.1464272721 -4.5758721847 +11558 52.1452174474 -4.5810844621 +11559 52.1436841082 -4.5860665862 +11560 52.1418435403 -4.5907656665 +11561 52.1397152906 -4.595131836 +11562 52.1373219582 -4.5991187822 +11563 52.1346889531 -4.6026842393 +11564 52.1318442253 -4.6057904364 +11565 52.1288179668 -4.6084044967 +11566 52.1256422898 -4.610498784 +11567 52.1223508853 -4.6120511927 +11568 52.1189786645 -4.6130453778 +11569 52.1155613879 -4.6134709236 +11570 52.1121352855 -4.613323449 +11571 52.1087366727 -4.6126046482 +11572 52.1054015654 -4.6113222675 +11573 52.1021652986 -4.6094900176 +11574 52.0990621525 -4.6071274234 +11575 52.0961249906 -4.6042596129 +11576 52.0933849121 -4.6009170469 +11577 52.090870924 -4.5971351939 +11578 52.0886096354 -4.5929541522 +11579 52.0866249767 -4.588418225 +11580 52.084937948 -4.5835754511 +11581 52.083566398 -4.5784770974 +11582 52.0825248361 -4.5731771188 +11583 52.0818242799 -4.5677315897 +11584 52.0814721395 -4.5621981139 +11585 52.0814721395 -4.5566352195 +11586 52.0818242799 -4.5511017437 +11587 52.0825248361 -4.5456562145 +11588 52.083566398 -4.5403562359 +11589 52.084937948 -4.5352578823 +11590 52.0866249767 -4.5304151083 +11591 52.0886096354 -4.5258791811 +11592 52.090870924 -4.5216981395 +11593 52.0933849121 -4.5179162864 +11594 52.0961249906 -4.5145737204 +11595 52.0990621525 -4.5117059099 +11596 52.1021652986 -4.5093433158 +11597 52.1054015654 -4.5075110659 +11598 52.1087366727 -4.5062286851 +11599 52.1121352855 -4.5055098843 +11600 52.1155613879 -4.5053624097 +11601 52.1189786645 -4.5057879555 +11602 52.1223508853 -4.5067821406 +11603 52.1256422898 -4.5083345493 +11604 52.1288179668 -4.5104288367 +11605 52.1318442253 -4.513042897 +11606 52.1346889531 -4.516149094 +11607 52.1373219582 -4.5197145511 +11608 52.1397152906 -4.5237014973 +11609 52.1418435403 -4.5280676668 +11610 52.1436841082 -4.5327667471 +11611 52.1452174474 -4.5377488713 +11612 52.1464272721 -4.5429611486 +11613 52.1473007313 -4.548348229 +11614 52.1478285462 -4.5538528938 +11615 52.1480051098 -4.5594166667 +11616 52.0952472222 -4.6350722222 +11617 52.1004781111 -4.6082841389 +11618 52.1032481534 -4.6101710488 +11619 52.1061116413 -4.6116450046 +11620 52.1090452778 -4.6126939167 +11621 52.1038166667 -4.6394694444 +11622 52.0952472222 -4.6350722222 +11623 52.1341194444 -4.4837666667 +11624 52.1289312222 -4.5105152222 +11625 52.1261593432 -4.5086338997 +11626 52.12329435 -4.5071664244 +11627 52.1203595833 -4.5061246944 +11628 52.12555 -4.4793638889 +11629 52.1341194444 -4.4837666667 +11630 52.6619383097 -3.1532972222 +11631 52.6617617591 -3.1589260268 +11632 52.661233983 -3.1644950299 +11633 52.6603605885 -3.1699450695 +11634 52.6591508538 -3.1752182559 +11635 52.6576176296 -3.1802585903 +11636 52.6557772011 -3.1850125627 +11637 52.6536491143 -3.1894297226 +11638 52.6512559674 -3.1934632159 +11639 52.6486231691 -3.1970702834 +11640 52.645778668 -3.2002127138 +11641 52.6427526543 -3.2028572478 +11642 52.6395772385 -3.2049759285 +11643 52.6362861091 -3.2065463945 +11644 52.6329141749 -3.2075521128 +11645 52.6294971935 -3.2079825492 +11646 52.6260713921 -3.2078332746 +11647 52.6226730826 -3.2071060066 +11648 52.6193382778 -3.2058085849 +11649 52.6161023088 -3.2039548833 +11650 52.6129994526 -3.2015646572 +11651 52.6100625687 -3.1986633301 +11652 52.6073227528 -3.1952817199 +11653 52.6048090084 -3.19145571 +11654 52.6025479412 -3.1872258673 +11655 52.6005634786 -3.1826370117 +11656 52.5988766179 -3.1777377416 +11657 52.5975052054 -3.1725799209 +11658 52.5964637484 -3.167218132 +11659 52.595763263 -3.1617091013 +11660 52.5954111583 -3.156111102 +11661 52.5954111583 -3.1504833424 +11662 52.595763263 -3.1448853432 +11663 52.5964637484 -3.1393763124 +11664 52.5975052054 -3.1340145236 +11665 52.5988766179 -3.1288567029 +11666 52.6005634786 -3.1239574328 +11667 52.6025479412 -3.1193685771 +11668 52.6048090084 -3.1151387345 +11669 52.6073227528 -3.1113127246 +11670 52.6100625687 -3.1079311144 +11671 52.6129994526 -3.1050297872 +11672 52.6161023088 -3.1026395612 +11673 52.6193382778 -3.1007858596 +11674 52.6226730826 -3.0994884379 +11675 52.6260713921 -3.0987611698 +11676 52.6294971935 -3.0986118953 +11677 52.6329141749 -3.0990423317 +11678 52.6362861091 -3.1000480499 +11679 52.6395772385 -3.1016185159 +11680 52.6427526543 -3.1037371966 +11681 52.645778668 -3.1063817306 +11682 52.6486231691 -3.109524161 +11683 52.6512559674 -3.1131312286 +11684 52.6536491143 -3.1171647219 +11685 52.6557772011 -3.1215818817 +11686 52.6576176296 -3.1263358541 +11687 52.6591508538 -3.1313761886 +11688 52.6603605885 -3.136649375 +11689 52.661233983 -3.1420994145 +11690 52.6617617591 -3.1476684176 +11691 52.6619383097 -3.1532972222 +11692 52.5861333333 -3.1928166667 +11693 52.5989991389 -3.1781366111 +11694 52.6004823189 -3.1824262144 +11695 52.6021947615 -3.186479086 +11696 52.6041225556 -3.19026225 +11697 52.5912638889 -3.2049305556 +11698 52.5861333333 -3.1928166667 +11699 52.671 -3.1138 +11700 52.6582820278 -3.1283630833 +11701 52.6567936288 -3.1240726758 +11702 52.6550759558 -3.1200207057 +11703 52.6531430278 -3.1162401944 +11704 52.6658694444 -3.1016638889 +11705 52.671 -3.1138 +11706 52.2749543894 -2.8811111111 +11707 52.274777829 -2.8866907656 +11708 52.2742500237 -2.8922111426 +11709 52.2733765806 -2.8976135985 +11710 52.2721667782 -2.9028407506 +11711 52.2706334675 -2.9078370904 +11712 52.2687929342 -2.9125495762 +11713 52.2666647249 -2.9169281982 +11714 52.2642714384 -2.9209265119 +11715 52.2616384845 -2.9245021309 +11716 52.2587938129 -2.9276171767 +11717 52.255767615 -2.9302386792 +11718 52.2525920027 -2.9323389239 +11719 52.2493006663 -2.9338957425 +11720 52.2459285165 -2.9348927443 +11721 52.2425113129 -2.9353194846 +11722 52.2390852849 -2.9351715705 +11723 52.2356867472 -2.934450702 +11724 52.2323517147 -2.9331646481 +11725 52.2291155216 -2.9313271595 +11726 52.2260124472 -2.9289578173 +11727 52.223075354 -2.9260818216 +11728 52.2203353404 -2.9227297205 +11729 52.2178214126 -2.9189370837 +11730 52.2155601787 -2.9147441241 +11731 52.2135755685 -2.910195271 +11732 52.2118885813 -2.9053386998 +11733 52.2105170653 -2.9002258233 +11734 52.2094755293 -2.8949107497 +11735 52.2087749906 -2.8894497124 +11736 52.208422859 -2.8839004789 +11737 52.208422859 -2.8783217433 +11738 52.2087749906 -2.8727725099 +11739 52.2094755293 -2.8673114726 +11740 52.2105170653 -2.8619963989 +11741 52.2118885813 -2.8568835225 +11742 52.2135755685 -2.8520269513 +11743 52.2155601787 -2.8474780981 +11744 52.2178214126 -2.8432851385 +11745 52.2203353404 -2.8394925017 +11746 52.223075354 -2.8361404006 +11747 52.2260124472 -2.8332644049 +11748 52.2291155216 -2.8308950627 +11749 52.2323517147 -2.8290575741 +11750 52.2356867472 -2.8277715202 +11751 52.2390852849 -2.8270506517 +11752 52.2425113129 -2.8269027376 +11753 52.2459285165 -2.8273294779 +11754 52.2493006663 -2.8283264797 +11755 52.2525920027 -2.8298832984 +11756 52.255767615 -2.831983543 +11757 52.2587938129 -2.8346050455 +11758 52.2616384845 -2.8377200913 +11759 52.2642714384 -2.8412957103 +11760 52.2666647249 -2.845294024 +11761 52.2687929342 -2.8496726461 +11762 52.2706334675 -2.8543851318 +11763 52.2721667782 -2.8593814716 +11764 52.2733765806 -2.8646086238 +11765 52.2742500237 -2.8700110796 +11766 52.274777829 -2.8755314566 +11767 52.2749543894 -2.8811111111 +11768 52.2310055556 -2.9589777778 +11769 52.2330216667 -2.9334707778 +11770 52.2359549995 -2.9345288123 +11771 52.2389349498 -2.9351518764 +11772 52.24193725 -2.9353348056 +11773 52.2399222222 -2.9608333333 +11774 52.2310055556 -2.9589777778 +11775 52.2522666667 -2.803475 +11776 52.2502995833 -2.828736 +11777 52.2473661174 -2.8276831046 +11778 52.2443863328 -2.8270654286 +11779 52.2413845 -2.8268879167 +11780 52.2433527778 -2.8016166667 +11781 52.2522666667 -2.803475 +11782 52.8671732622 -2.7716666667 +11783 52.8669967167 -2.7773219972 +11784 52.8664689561 -2.7829172434 +11785 52.8655955872 -2.7883929636 +11786 52.8643858882 -2.7936909943 +11787 52.8628527096 -2.7987550722 +11788 52.8610123364 -2.8035314345 +11789 52.8588843143 -2.8079693927 +11790 52.8564912409 -2.8120218721 +11791 52.8538585248 -2.8156459119 +11792 52.8510141137 -2.8188031213 +11793 52.8479881974 -2.8214600849 +11794 52.8448128853 -2.8235887151 +11795 52.8415218654 -2.8251665461 +11796 52.8381500451 -2.8261769682 +11797 52.8347331812 -2.8266093991 +11798 52.8313074995 -2.82645939 +11799 52.8279093109 -2.8257286679 +11800 52.8245746265 -2.8244251109 +11801 52.8213387762 -2.8225626591 +11802 52.8182360355 -2.8201611621 +11803 52.8152992624 -2.8172461638 +11804 52.8125595511 -2.8138486278 +11805 52.8100459039 -2.8100046069 +11806 52.807784925 -2.805754859 +11807 52.8058005407 -2.8011444147 +11808 52.8041137471 -2.7962221007 +11809 52.8027423894 -2.7910400244 +11810 52.8017009742 -2.7856530242 +11811 52.8010005171 -2.7801180923 +11812 52.8006484267 -2.7744937751 +11813 52.8006484267 -2.7688395582 +11814 52.8010005171 -2.763215241 +11815 52.8017009742 -2.7576803091 +11816 52.8027423894 -2.7522933089 +11817 52.8041137471 -2.7471112326 +11818 52.8058005407 -2.7421889187 +11819 52.807784925 -2.7375784743 +11820 52.8100459039 -2.7333287264 +11821 52.8125595511 -2.7294847055 +11822 52.8152992624 -2.7260871695 +11823 52.8182360355 -2.7231721712 +11824 52.8213387762 -2.7207706742 +11825 52.8245746265 -2.7189082225 +11826 52.8279093109 -2.7176046654 +11827 52.8313074995 -2.7168739433 +11828 52.8347331812 -2.7167239343 +11829 52.8381500451 -2.7171563651 +11830 52.8415218654 -2.7181667872 +11831 52.8448128853 -2.7197446182 +11832 52.8479881974 -2.7218732484 +11833 52.8510141137 -2.7245302121 +11834 52.8538585248 -2.7276874215 +11835 52.8564912409 -2.7313114613 +11836 52.8588843143 -2.7353639406 +11837 52.8610123364 -2.7398018988 +11838 52.8628527096 -2.7445782612 +11839 52.8643858882 -2.7496423391 +11840 52.8655955872 -2.7549403698 +11841 52.8664689561 -2.7604160899 +11842 52.8669967167 -2.7660113361 +11843 52.8671732622 -2.7716666667 +11844 52.796675 -2.8230305556 +11845 52.8074808889 -2.8051105556 +11846 52.8094142415 -2.8089038559 +11847 52.8115468244 -2.8123944447 +11848 52.8138613056 -2.8155538889 +11849 52.80305 -2.8334805556 +11850 52.796675 -2.8230305556 +11851 52.8714472222 -2.7198416667 +11852 52.8603496111 -2.7383165278 +11853 52.8584212007 -2.7345122636 +11854 52.8562929696 -2.7310110402 +11855 52.8539822778 -2.7278413611 +11856 52.865075 -2.7093722222 +11857 52.8714472222 -2.7198416667 +11858 52.8812833333 -2.7795583333 +11859 52.8668773056 -2.7789823611 +11860 52.8671423114 -2.7740367547 +11861 52.8671361609 -2.7690717949 +11862 52.8668588889 -2.7641280278 +11863 52.8815 -2.7647083333 +11864 52.8812833333 -2.7795583333 +11865 52.7847416667 -2.7608805556 +11866 52.8011758333 -2.7615295 +11867 52.8007554016 -2.7664380394 +11868 52.8006047438 -2.7713890858 +11869 52.8007250833 -2.7763423889 +11870 52.7845277778 -2.7756972222 +11871 52.7847416667 -2.7608805556 +11872 52.8269096004 -2.6679388889 +11873 52.8267330539 -2.67358899 +11874 52.8262052903 -2.6791790626 +11875 52.8253319163 -2.6846497199 +11876 52.8241222104 -2.6899428528 +11877 52.8225890229 -2.6950022498 +11878 52.8207486388 -2.6997741981 +11879 52.818620604 -2.7042080561 +11880 52.8162275163 -2.7082567924 +11881 52.813594784 -2.7118774863 +11882 52.8107503553 -2.7150317821 +11883 52.8077244199 -2.7176862954 +11884 52.8045490875 -2.7198129641 +11885 52.8012580461 -2.7213893431 +11886 52.7978862036 -2.7223988379 +11887 52.7944693166 -2.7228308756 +11888 52.7910436115 -2.7226810114 +11889 52.7876453991 -2.7219509703 +11890 52.7843106911 -2.7206486227 +11891 52.7810748176 -2.718787896 +11892 52.7779720542 -2.716388621 +11893 52.7750352593 -2.7134763179 +11894 52.7722955276 -2.7100819216 +11895 52.7697818613 -2.7062414514 +11896 52.7675208651 -2.7019956277 +11897 52.7655364654 -2.6973894394 +11898 52.7638496586 -2.6924716684 +11899 52.7624782902 -2.6872943739 +11900 52.7614368668 -2.6819123439 +11901 52.7607364042 -2.6763825182 +11902 52.7603843109 -2.6707633894 +11903 52.7603843109 -2.6651143884 +11904 52.7607364042 -2.6594952596 +11905 52.7614368668 -2.6539654339 +11906 52.7624782902 -2.6485834039 +11907 52.7638496586 -2.6434061094 +11908 52.7655364654 -2.6384883384 +11909 52.7675208651 -2.6338821501 +11910 52.7697818613 -2.6296363263 +11911 52.7722955276 -2.6257958562 +11912 52.7750352593 -2.6224014599 +11913 52.7779720542 -2.6194891568 +11914 52.7810748176 -2.6170898818 +11915 52.7843106911 -2.615229155 +11916 52.7876453991 -2.6139268075 +11917 52.7910436115 -2.6131967664 +11918 52.7944693166 -2.6130469022 +11919 52.7978862036 -2.6134789398 +11920 52.8012580461 -2.6144884347 +11921 52.8045490875 -2.6160648137 +11922 52.8077244199 -2.6181914824 +11923 52.8107503553 -2.6208459957 +11924 52.813594784 -2.6240002915 +11925 52.8162275163 -2.6276209853 +11926 52.818620604 -2.6316697217 +11927 52.8207486388 -2.6361035797 +11928 52.8225890229 -2.640875528 +11929 52.8241222104 -2.645934925 +11930 52.8253319163 -2.6512280578 +11931 52.8262052903 -2.6566987152 +11932 52.8267330539 -2.6622887877 +11933 52.8269096004 -2.6679388889 +11934 52.7576245833 -2.7235820278 +11935 52.7690354444 -2.7049352778 +11936 52.7711671052 -2.7084554449 +11937 52.7734832474 -2.7116432321 +11938 52.7759648611 -2.7144724444 +11939 52.7639548056 -2.7340958611 +11940 52.7576245833 -2.7235820278 +11941 52.8365074722 -2.6153044722 +11942 52.8219718889 -2.6391511389 +11943 52.8202752714 -2.6350330637 +11944 52.8183596115 -2.631185824 +11945 52.8162406667 -2.6276410556 +11946 52.8301773333 -2.6047731389 +11947 52.8365074722 -2.6153044722 +11948 52.84677375 -2.6755396111 +11949 52.8265954444 -2.6754679167 +11950 52.826872528 -2.6705304301 +11951 52.8268786728 -2.6655717917 +11952 52.8266138333 -2.6606324722 +11953 52.8467921389 -2.6606972778 +11954 52.84677375 -2.6755396111 +11955 52.7404752778 -2.6603565556 +11956 52.7606538889 -2.6604210833 +11957 52.7603772366 -2.6653511557 +11958 52.7603710937 -2.6703022476 +11959 52.7606355278 -2.6752341389 +11960 52.7404568889 -2.6751627778 +11961 52.7404752778 -2.6603565556 +11962 52.9064452629 -2.5321916667 +11963 52.9062687185 -2.5378521099 +11964 52.9057409608 -2.5434524143 +11965 52.9048675968 -2.5489330842 +11966 52.9036579047 -2.5542359034 +11967 52.9021247347 -2.5593045577 +11968 52.9002843721 -2.5640852355 +11969 52.8981563623 -2.5685272025 +11970 52.895763303 -2.5725833412 +11971 52.8931306025 -2.5762106523 +11972 52.8902862087 -2.5793707102 +11973 52.8872603109 -2.5820300695 +11974 52.8840850187 -2.5841606174 +11975 52.8807940196 -2.5857398679 +11976 52.8774222212 -2.5867511966 +11977 52.8740053798 -2.5871840119 +11978 52.870579721 -2.5870338612 +11979 52.8671815554 -2.5863024734 +11980 52.863846894 -2.5849977337 +11981 52.8606110665 -2.5831335954 +11982 52.8575083478 -2.5807299261 +11983 52.8545715958 -2.5778122927 +11984 52.8518319046 -2.5744116872 +11985 52.849318276 -2.5705641948 +11986 52.847057314 -2.5663106103 +11987 52.8450729446 -2.5616960049 +11988 52.8433861638 -2.5567692495 +11989 52.8420148166 -2.5515824981 +11990 52.8409734095 -2.5461906387 +11991 52.8402729578 -2.5406507145 +11992 52.8399208701 -2.5350213248 +11993 52.8399208701 -2.5293620085 +11994 52.8402729578 -2.5237326188 +11995 52.8409734095 -2.5181926947 +11996 52.8420148166 -2.5128008352 +11997 52.8433861638 -2.5076140839 +11998 52.8450729446 -2.5026873284 +11999 52.847057314 -2.498072723 +12000 52.849318276 -2.4938191385 +12001 52.8518319046 -2.4899716461 +12002 52.8545715958 -2.4865710406 +12003 52.8575083478 -2.4836534073 +12004 52.8606110665 -2.4812497379 +12005 52.863846894 -2.4793855996 +12006 52.8671815554 -2.47808086 +12007 52.870579721 -2.4773494721 +12008 52.8740053798 -2.4771993215 +12009 52.8774222212 -2.4776321367 +12010 52.8807940196 -2.4786434655 +12011 52.8840850187 -2.480222716 +12012 52.8872603109 -2.4823532638 +12013 52.8902862087 -2.4850126232 +12014 52.8931306025 -2.4881726811 +12015 52.895763303 -2.4917999922 +12016 52.8981563623 -2.4958561309 +12017 52.9002843721 -2.5002980978 +12018 52.9021247347 -2.5050787756 +12019 52.9036579047 -2.5101474299 +12020 52.9048675968 -2.5154502492 +12021 52.9057409608 -2.520930919 +12022 52.9062687185 -2.5265312234 +12023 52.9064452629 -2.5321916667 +12024 52.8343893333 -2.5805501389 +12025 52.8457666667 -2.5634260556 +12026 52.847581813 -2.5673785486 +12027 52.8496051651 -2.5710450266 +12028 52.8518202778 -2.5743956389 +12029 52.8404460278 -2.5915122222 +12030 52.8343893333 -2.5805501389 +12031 52.9119084722 -2.4837607222 +12032 52.900549 -2.5009221944 +12033 52.8987318797 -2.4969673837 +12034 52.8967064683 -2.4932998953 +12035 52.8944892778 -2.4899496111 +12036 52.9058518611 -2.4727806111 +12037 52.9119084722 -2.4837607222 +12038 52.8759196389 -2.6141188611 +12039 52.8733867778 -2.5872000556 +12040 52.876386522 -2.5869443115 +12041 52.879360097 -2.5862425569 +12042 52.8822832778 -2.5851004167 +12043 52.8847976389 -2.6118228056 +12044 52.8759196389 -2.6141188611 +12045 52.8699211389 -2.4546785556 +12046 52.8720677778 -2.4772125278 +12047 52.8690732605 -2.4776011819 +12048 52.8661121323 -2.4784342929 +12049 52.8632085 -2.479705 +12050 52.8610431111 -2.4569738333 +12051 52.8699211389 -2.4546785556 +12052 52.9203575 -2.5527453056 +12053 52.9051048889 -2.547651 +12054 52.9058186705 -2.5428192861 +12055 52.906265669 -2.5379006231 +12056 52.9064422222 -2.53293525 +12057 52.9221333889 -2.5381707222 +12058 52.9203575 -2.5527453056 +12059 52.8270092778 -2.50649125 +12060 52.8423044722 -2.5115754722 +12061 52.84130443 -2.5162593978 +12062 52.8405642633 -2.5210730991 +12063 52.84009 -2.5259773611 +12064 52.8252333889 -2.521034 +12065 52.8270092778 -2.50649125 +12066 52.6737854649 -2.3052 +12067 52.6736089147 -2.3108303271 +12068 52.6730811395 -2.3164008364 +12069 52.6722077464 -2.3218523499 +12070 52.6709980139 -2.3271269622 +12071 52.6694647923 -2.3321686594 +12072 52.6676243669 -2.3369239169 +12073 52.6654962839 -2.3413422704 +12074 52.6631031412 -2.3453768535 +12075 52.6604703477 -2.3489848951 +12076 52.6576258518 -2.3521281738 +12077 52.6545998437 -2.3547734212 +12078 52.6514244339 -2.356892673 +12079 52.6481333109 -2.3584635616 +12080 52.6447613832 -2.3594695499 +12081 52.6413444087 -2.3599001008 +12082 52.6379186141 -2.3597507841 +12083 52.6345203117 -2.3590233178 +12084 52.6311855137 -2.3577255439 +12085 52.6279495517 -2.3558713401 +12086 52.6248467021 -2.3534804672 +12087 52.6219098246 -2.3505783554 +12088 52.6191700147 -2.3471958311 +12089 52.6166562759 -2.3433687875 +12090 52.6143952138 -2.3391378023 +12091 52.6124107558 -2.3345477076 +12092 52.610723899 -2.3296471149 +12093 52.6093524896 -2.3244879021 +12094 52.608311035 -2.3191246662 +12095 52.6076105513 -2.3136141488 +12096 52.6072584474 -2.3080146391 +12097 52.6072584474 -2.3023853609 +12098 52.6076105513 -2.2967858512 +12099 52.608311035 -2.2912753338 +12100 52.6093524896 -2.2859120979 +12101 52.610723899 -2.2807528851 +12102 52.6124107558 -2.2758522924 +12103 52.6143952138 -2.2712621977 +12104 52.6166562759 -2.2670312125 +12105 52.6191700147 -2.2632041689 +12106 52.6219098246 -2.2598216446 +12107 52.6248467021 -2.2569195328 +12108 52.6279495517 -2.2545286599 +12109 52.6311855137 -2.2526744561 +12110 52.6345203117 -2.2513766822 +12111 52.6379186141 -2.2506492159 +12112 52.6413444087 -2.2504998992 +12113 52.6447613832 -2.2509304501 +12114 52.6481333109 -2.2519364384 +12115 52.6514244339 -2.253507327 +12116 52.6545998437 -2.2556265788 +12117 52.6576258518 -2.2582718262 +12118 52.6604703477 -2.2614151049 +12119 52.6631031412 -2.2650231465 +12120 52.6654962839 -2.2690577296 +12121 52.6676243669 -2.2734760831 +12122 52.6694647923 -2.2782313406 +12123 52.6709980139 -2.2832730378 +12124 52.6722077464 -2.2885476501 +12125 52.6730811395 -2.2939991636 +12126 52.6736089147 -2.2995696729 +12127 52.6737854649 -2.3052 +12128 52.6102927222 -2.3708121389 +12129 52.619248 -2.3473025278 +12130 52.6216433353 -2.3502802235 +12131 52.624192216 -2.3528913183 +12132 52.6268739167 -2.3551145 +12133 52.6179139722 -2.3786348056 +12134 52.6102927222 -2.3708121389 +12135 52.6707405556 -2.2396455556 +12136 52.6618198889 -2.26317 +12137 52.6594282563 -2.2601815668 +12138 52.6568824958 -2.2575601865 +12139 52.6542033611 -2.2553271667 +12140 52.6631193889 -2.2318134444 +12141 52.6707405556 -2.2396455556 +12142 52.6108995278 -2.3714746389 +12143 52.6198109722 -2.3480534722 +12144 52.6222458531 -2.3509455268 +12145 52.6248294636 -2.3534653466 +12146 52.6275407778 -2.3555923611 +12147 52.6185231667 -2.3792911389 +12148 52.6108995278 -2.3714746389 +12149 52.6710197778 -2.2410140556 +12150 52.6623476389 -2.2639089722 +12151 52.6599937279 -2.260838454 +12152 52.6574809994 -2.2581298286 +12153 52.6548299444 -2.2558051389 +12154 52.6633962222 -2.2331881944 +12155 52.6710197778 -2.2410140556 +12156 52.5506694943 -2.2595472222 +12157 52.550492941 -2.2651617798 +12158 52.5499651565 -2.2707166877 +12159 52.549091748 -2.2761529343 +12160 52.547881994 -2.2814127768 +12161 52.5463487449 -2.2864403587 +12162 52.5445082863 -2.2911823054 +12163 52.5423801644 -2.2955882944 +12164 52.5399869775 -2.2996115904 +12165 52.5373541345 -2.303209542 +12166 52.5345095845 -2.3063440346 +12167 52.5314835179 -2.3089818926 +12168 52.5283080457 -2.3110952293 +12169 52.5250168569 -2.3126617395 +12170 52.5216448608 -2.3136649312 +12171 52.5182278157 -2.3140942963 +12172 52.5148019491 -2.3139454162 +12173 52.5114035741 -2.3132200032 +12174 52.5080687039 -2.3119258767 +12175 52.5048326706 -2.3100768748 +12176 52.5017297516 -2.3076927023 +12177 52.4987928076 -2.3047987179 +12178 52.4960529349 -2.3014256614 +12179 52.4935391378 -2.2976093253 +12180 52.4912780227 -2.2933901738 +12181 52.4892935177 -2.2888129135 +12182 52.4876066206 -2.2839260204 +12183 52.4862351784 -2.2787812274 +12184 52.4851936987 -2.2734329797 +12185 52.484493198 -2.2679378606 +12186 52.4841410855 -2.2623539968 +12187 52.4841410855 -2.2567404476 +12188 52.484493198 -2.2511565839 +12189 52.4851936987 -2.2456614647 +12190 52.4862351784 -2.240313217 +12191 52.4876066206 -2.2351684241 +12192 52.4892935177 -2.2302815309 +12193 52.4912780227 -2.2257042707 +12194 52.4935391378 -2.2214851191 +12195 52.4960529349 -2.217668783 +12196 52.4987928076 -2.2142957265 +12197 52.5017297516 -2.2114017421 +12198 52.5048326706 -2.2090175697 +12199 52.5080687039 -2.2071685677 +12200 52.5114035741 -2.2058744412 +12201 52.5148019491 -2.2051490283 +12202 52.5182278157 -2.2050001482 +12203 52.5216448608 -2.2054295133 +12204 52.5250168569 -2.206432705 +12205 52.5283080457 -2.2079992151 +12206 52.5314835179 -2.2101125519 +12207 52.5345095845 -2.2127504099 +12208 52.5373541345 -2.2158849024 +12209 52.5399869775 -2.2194828541 +12210 52.5423801644 -2.22350615 +12211 52.5445082863 -2.227912139 +12212 52.5463487449 -2.2326540858 +12213 52.547881994 -2.2376816676 +12214 52.549091748 -2.2429415102 +12215 52.5499651565 -2.2483777568 +12216 52.550492941 -2.2539326647 +12217 52.5506694943 -2.2595472222 +12218 52.4777166667 -2.3045555556 +12219 52.4897268611 -2.2899011667 +12220 52.4915154092 -2.2938762625 +12221 52.4935160039 -2.2975703338 +12222 52.4957122778 -2.3009530833 +12223 52.4830888889 -2.3163527778 +12224 52.4777166667 -2.3045555556 +12225 52.5588416667 -2.2237694444 +12226 52.5477822778 -2.2373114444 +12227 52.5464304954 -2.2328922036 +12228 52.54484039 -2.2286919692 +12229 52.5430250278 -2.2247452222 +12230 52.5534722222 -2.21195 +12231 52.5588416667 -2.2237694444 +12232 52.5595916667 -2.2987055556 +12233 52.54563275 -2.2884155278 +12234 52.5471052761 -2.2841209325 +12235 52.5483356141 -2.2796258124 +12236 52.5493137222 -2.2749668333 +12237 52.5632694444 -2.28525 +12238 52.5595916667 -2.2987055556 +12239 52.4749055556 -2.2202611111 +12240 52.4891311944 -2.2307041944 +12241 52.4876600186 -2.2349940211 +12242 52.4864307253 -2.2394833707 +12243 52.4854533056 -2.24413575 +12244 52.471225 -2.2336861111 +12245 52.4749055556 -2.2202611111 +12246 52.8473539295 -1.7647083333 +12247 52.8471773836 -1.7703610882 +12248 52.8466496214 -1.7759537862 +12249 52.8457762501 -1.7814270127 +12250 52.8445665477 -1.786722631 +12251 52.8430333647 -1.7917844034 +12252 52.8411929861 -1.7965585917 +12253 52.8390649577 -1.8009945304 +12254 52.8366718773 -1.8050451662 +12255 52.8340391532 -1.808667558 +12256 52.8311947335 -1.8118233323 +12257 52.8281688078 -1.8144790891 +12258 52.8249934857 -1.8166067531 +12259 52.8217024552 -1.818183869 +12260 52.818330624 -1.8191938344 +12261 52.8149137488 -1.8196260716 +12262 52.8114880555 -1.8194761339 +12263 52.8080898552 -1.8187457472 +12264 52.8047551592 -1.8174427859 +12265 52.8015192975 -1.8155811838 +12266 52.7984165455 -1.8131807812 +12267 52.7954797617 -1.8102671103 +12268 52.7927400404 -1.8068711208 +12269 52.7902263838 -1.8030288488 +12270 52.7879653964 -1.7987810336 +12271 52.7859810045 -1.7941726856 +12272 52.7842942044 -1.7892526091 +12273 52.7829228414 -1.7840728881 +12274 52.7818814222 -1.7786883359 +12275 52.7811809624 -1.773155919 +12276 52.7808288706 -1.7675341573 +12277 52.7808288706 -1.7618825094 +12278 52.7811809624 -1.7562607477 +12279 52.7818814222 -1.7507283308 +12280 52.7829228414 -1.7453437786 +12281 52.7842942044 -1.7401640575 +12282 52.7859810045 -1.7352439811 +12283 52.7879653964 -1.730635633 +12284 52.7902263838 -1.7263878179 +12285 52.7927400404 -1.7225455459 +12286 52.7954797617 -1.7191495563 +12287 52.7984165455 -1.7162358855 +12288 52.8015192975 -1.7138354829 +12289 52.8047551592 -1.7119738808 +12290 52.8080898552 -1.7106709195 +12291 52.8114880555 -1.7099405328 +12292 52.8149137488 -1.7097905951 +12293 52.818330624 -1.7102228322 +12294 52.8217024552 -1.7112327977 +12295 52.8249934857 -1.7128099135 +12296 52.8281688078 -1.7149375776 +12297 52.8311947335 -1.7175933343 +12298 52.8340391532 -1.7207491087 +12299 52.8366718773 -1.7243715005 +12300 52.8390649577 -1.7284221363 +12301 52.8411929861 -1.7328580749 +12302 52.8430333647 -1.7376322632 +12303 52.8445665477 -1.7426940356 +12304 52.8457762501 -1.7479896539 +12305 52.8466496214 -1.7534628805 +12306 52.8471773836 -1.7590555784 +12307 52.8473539295 -1.7647083333 +12308 52.7956138889 -1.8422166667 +12309 52.8004843611 -1.8148514167 +12310 52.8032777906 -1.8166692181 +12311 52.8061591203 -1.8180644306 +12312 52.8091049167 -1.8190256111 +12313 52.8042361111 -1.8463805556 +12314 52.7956138889 -1.8422166667 +12315 52.8324722222 -1.6871555556 +12316 52.8276346944 -1.7145350278 +12317 52.8248396575 -1.7127224882 +12318 52.8219570266 -1.7113333994 +12319 52.8190102778 -1.710379 +12320 52.82385 -1.6829861111 +12321 52.8324722222 -1.6871555556 +12322 52.4977192163 -1.7505555556 +12323 52.497541557 -1.7568458982 +12324 52.4970100989 -1.763082423 +12325 52.496129389 -1.7692117761 +12326 52.4949069615 -1.7751815286 +12327 52.4933532735 -1.7809406276 +12328 52.4914816145 -1.7864398366 +12329 52.4893079919 -1.7916321586 +12330 52.4868509931 -1.7964732401 +12331 52.4841316255 -1.8009217512 +12332 52.4811731357 -1.8049397389 +12333 52.4780008096 -1.8084929515 +12334 52.4746417551 -1.8115511291 +12335 52.4711246695 -1.8140882605 +12336 52.467479593 -1.8160828021 +12337 52.4637376518 -1.8175178582 +12338 52.4599307911 -1.8183813209 +12339 52.4560915023 -1.818665969 +12340 52.4522525448 -1.8183695247 +12341 52.448446667 -1.8174946675 +12342 52.4447063266 -1.8160490067 +12343 52.4410634144 -1.8140450112 +12344 52.4375489828 -1.8114998987 +12345 52.4341929817 -1.8084354845 +12346 52.4310240045 -1.8048779924 +12347 52.4280690449 -1.8008578279 +12348 52.4253532687 -1.7964093168 +12349 52.4228998002 -1.7915704121 +12350 52.4207295265 -1.7863823696 +12351 52.4188609209 -1.7808893971 +12352 52.417309887 -1.7751382792 +12353 52.4160896238 -1.7691779807 +12354 52.4152105147 -1.7630592323 +12355 52.4146800394 -1.756834102 +12356 52.4145027115 -1.7505555556 +12357 52.4146800394 -1.7442770091 +12358 52.4152105147 -1.7380518788 +12359 52.4160896238 -1.7319331305 +12360 52.417309887 -1.7259728319 +12361 52.4188609209 -1.720221714 +12362 52.4207295265 -1.7147287415 +12363 52.4228998002 -1.709540699 +12364 52.4253532687 -1.7047017943 +12365 52.4280690449 -1.7002532833 +12366 52.4310240045 -1.6962331187 +12367 52.4341929817 -1.6926756266 +12368 52.4375489828 -1.6896112124 +12369 52.4410634144 -1.6870660999 +12370 52.4447063266 -1.6850621044 +12371 52.448446667 -1.6836164436 +12372 52.4522525448 -1.6827415864 +12373 52.4560915023 -1.6824451421 +12374 52.4599307911 -1.6827297903 +12375 52.4637376518 -1.6835932529 +12376 52.467479593 -1.685028309 +12377 52.4711246695 -1.6870228506 +12378 52.4746417551 -1.689559982 +12379 52.4780008096 -1.6926181596 +12380 52.4811731357 -1.6961713722 +12381 52.4841316255 -1.7001893599 +12382 52.4868509931 -1.704637871 +12383 52.4893079919 -1.7094789525 +12384 52.4914816145 -1.7146712746 +12385 52.4933532735 -1.7201704835 +12386 52.4949069615 -1.7259295825 +12387 52.496129389 -1.731899335 +12388 52.4970100989 -1.7380286881 +12389 52.497541557 -1.7442652129 +12390 52.4977192163 -1.7505555556 +12391 52.4981111111 -1.8062 +12392 52.48780075 -1.7947085 +12393 52.4896625365 -1.7908524655 +12394 52.4913496605 -1.7867862897 +12395 52.4928533333 -1.7825311667 +12396 52.5031611111 -1.7940166667 +12397 52.4981111111 -1.8062 +12398 52.4116166667 -1.6922444444 +12399 52.4244166667 -1.7064432222 +12400 52.4225567709 -1.7102953441 +12401 52.4208713218 -1.7143564184 +12402 52.4193690556 -1.7186053333 +12403 52.4065666667 -1.7044 +12404 52.4116166667 -1.6922444444 +12405 52.8930064498 -1.6175 +12406 52.892829905 -1.6231586924 +12407 52.8923021463 -1.6287572645 +12408 52.8914287806 -1.6342362393 +12409 52.8902190862 -1.6395374187 +12410 52.8886859133 -1.6446045057 +12411 52.886845547 -1.6493837057 +12412 52.884717533 -1.6538242998 +12413 52.8823244689 -1.6578791853 +12414 52.8796917631 -1.6615053761 +12415 52.8768473633 -1.6646644585 +12416 52.8738214592 -1.6673229974 +12417 52.8706461602 -1.6694528885 +12418 52.867355154 -1.6710316529 +12419 52.8639833481 -1.6720426712 +12420 52.860566499 -1.6724753548 +12421 52.8571408323 -1.6723252526 +12422 52.8537426589 -1.6715940928 +12423 52.8504079896 -1.6702897581 +12424 52.8471721543 -1.6684261974 +12425 52.8440694281 -1.666023272 +12426 52.8411326689 -1.663106541 +12427 52.8383929708 -1.6597069867 +12428 52.8358793358 -1.6558606832 +12429 52.8336183681 -1.6516084125 +12430 52.8316339936 -1.6469952321 +12431 52.8299472084 -1.6420699977 +12432 52.8285758576 -1.6368848474 +12433 52.8275344477 -1.631494652 +12434 52.8268339942 -1.6259564376 +12435 52.8264819055 -1.620328785 +12436 52.8264819055 -1.614671215 +12437 52.8268339942 -1.6090435624 +12438 52.8275344477 -1.603505348 +12439 52.8285758576 -1.5981151526 +12440 52.8299472084 -1.5929300023 +12441 52.8316339936 -1.5880047679 +12442 52.8336183681 -1.5833915875 +12443 52.8358793358 -1.5791393168 +12444 52.8383929708 -1.5752930133 +12445 52.8411326689 -1.571893459 +12446 52.8440694281 -1.568976728 +12447 52.8471721543 -1.5665738026 +12448 52.8504079896 -1.5647102419 +12449 52.8537426589 -1.5634059072 +12450 52.8571408323 -1.5626747474 +12451 52.860566499 -1.5625246452 +12452 52.8639833481 -1.5629573288 +12453 52.867355154 -1.5639683471 +12454 52.8706461602 -1.5655471115 +12455 52.8738214592 -1.5676770026 +12456 52.8768473633 -1.5703355415 +12457 52.8796917631 -1.5734946239 +12458 52.8823244689 -1.5771208147 +12459 52.884717533 -1.5811757002 +12460 52.886845547 -1.5856162943 +12461 52.8886859133 -1.5903954943 +12462 52.8902190862 -1.5954625813 +12463 52.8914287806 -1.6007637607 +12464 52.8923021463 -1.6062427355 +12465 52.892829905 -1.6118413076 +12466 52.8930064498 -1.6175 +12467 52.8241792222 -1.6682780278 +12468 52.8335263333 -1.6514153333 +12469 52.8354843292 -1.6551790821 +12470 52.8376398054 -1.6586362529 +12471 52.8399752222 -1.6617586667 +12472 52.8308118889 -1.6782875556 +12473 52.8241792222 -1.6682780278 +12474 52.8933006111 -1.5653483889 +12475 52.8846404444 -1.5810313611 +12476 52.8825482362 -1.5774659925 +12477 52.8802699556 -1.5742274102 +12478 52.8778241944 -1.571342 +12479 52.886668 -1.5553245 +12480 52.8933006111 -1.5653483889 +12481 52.8621813611 -1.6926618056 +12482 52.8605240556 -1.6724770556 +12483 52.8635213229 -1.6721355166 +12484 52.866487734 -1.6713486888 +12485 52.8693991111 -1.6701229167 +12486 52.8710847222 -1.6906521111 +12487 52.8621813611 -1.6926618056 +12488 52.8586619444 -1.5403897778 +12489 52.8605040833 -1.5625221667 +12490 52.857500432 -1.5626315478 +12491 52.8545149834 -1.5631879018 +12492 52.8515720556 -1.5641866111 +12493 52.8497585556 -1.5423988889 +12494 52.8586619444 -1.5403897778 +12495 52.9061841944 -1.63679225 +12496 52.8916396667 -1.6331029167 +12497 52.8923609231 -1.6282821584 +12498 52.8928162187 -1.6233734078 +12499 52.8930018333 -1.6184167222 +12500 52.9075444444 -1.6221006389 +12501 52.9061841944 -1.63679225 +12502 52.8136583611 -1.5983614722 +12503 52.8278006389 -1.6019306944 +12504 52.8270810369 -1.6067449988 +12505 52.8266270276 -1.6116466805 +12506 52.8264423056 -1.6165959167 +12507 52.8122980833 -1.6130214167 +12508 52.8136583611 -1.5983614722 +12509 52.2254963366 -1.6144 +12510 52.225319775 -1.6199734531 +12511 52.2247919659 -1.6254876949 +12512 52.2239185166 -1.6308841471 +12513 52.2227087055 -1.636105491 +12514 52.2211753837 -1.64109628 +12515 52.2193348369 -1.6458035312 +12516 52.2172066119 -1.6501772909 +12517 52.2148133076 -1.6541711659 +12518 52.2121803337 -1.6577428169 +12519 52.2093356402 -1.6608544075 +12520 52.2063094187 -1.663473004 +12521 52.2031337812 -1.6655709225 +12522 52.1998424183 -1.6671260192 +12523 52.1964702408 -1.6681219212 +12524 52.1930530088 -1.6685481951 +12525 52.1896269519 -1.6684004526 +12526 52.1862283849 -1.6676803914 +12527 52.1828933233 -1.6663957719 +12528 52.1796571014 -1.6645603288 +12529 52.1765539991 -1.6621936216 +12530 52.1736168792 -1.659320822 +12531 52.1708768403 -1.6559724441 +12532 52.168362889 -1.652184018 +12533 52.1661016338 -1.6479957121 +12534 52.1641170047 -1.6434519062 +12535 52.1624300014 -1.6386007224 +12536 52.1610584721 -1.6334935167 +12537 52.160016926 -1.6281843373 +12538 52.1593163805 -1.6227293555 +12539 52.1589642455 -1.617186275 +12540 52.1589642455 -1.611613725 +12541 52.1593163805 -1.6060706445 +12542 52.160016926 -1.6006156627 +12543 52.1610584721 -1.5953064833 +12544 52.1624300014 -1.5901992776 +12545 52.1641170047 -1.5853480938 +12546 52.1661016338 -1.5808042879 +12547 52.168362889 -1.576615982 +12548 52.1708768403 -1.5728275559 +12549 52.1736168792 -1.569479178 +12550 52.1765539991 -1.5666063784 +12551 52.1796571014 -1.5642396712 +12552 52.1828933233 -1.5624042281 +12553 52.1862283849 -1.5611196086 +12554 52.1896269519 -1.5603995474 +12555 52.1930530088 -1.5602518049 +12556 52.1964702408 -1.5606780788 +12557 52.1998424183 -1.5616739808 +12558 52.2031337812 -1.5632290775 +12559 52.2063094187 -1.565326996 +12560 52.2093356402 -1.5679455925 +12561 52.2121803337 -1.5710571831 +12562 52.2148133076 -1.5746288341 +12563 52.2172066119 -1.5786227091 +12564 52.2193348369 -1.5829964688 +12565 52.2211753837 -1.58770372 +12566 52.2227087055 -1.592694509 +12567 52.2239185166 -1.5979158529 +12568 52.2247919659 -1.6033123051 +12569 52.225319775 -1.6088265469 +12570 52.2254963366 -1.6144 +12571 52.1525 -1.6644833333 +12572 52.1645690833 -1.6445776111 +12573 52.1663578639 -1.6485160735 +12574 52.1683580392 -1.6521759225 +12575 52.1705532778 -1.6555272222 +12576 52.1589055556 -1.6747361111 +12577 52.1525 -1.6644833333 +12578 52.2256444444 -1.5644666667 +12579 52.2171532222 -1.5785241667 +12580 52.2150594228 -1.5750030605 +12581 52.2127787035 -1.5718046369 +12582 52.21032975 -1.5689550278 +12583 52.2192416667 -1.5542 +12584 52.2256444444 -1.5644666667 +12585 52.240825 -1.6271083333 +12586 52.2248114167 -1.6253352222 +12587 52.2252843723 -1.6205050805 +12588 52.2254878269 -1.6156251224 +12589 52.2254201111 -1.6107351667 +12590 52.2414333333 -1.6125027778 +12591 52.240825 -1.6271083333 +12592 52.1435888889 -1.6017222222 +12593 52.1596037222 -1.6034835 +12594 52.1591316218 -1.6083064442 +12595 52.1589286094 -1.6131788875 +12596 52.1589963333 -1.61806125 +12597 52.1429805556 -1.6162944444 +12598 52.1435888889 -1.6017222222 +12599 52.4114198271 -1.4796805556 +12600 52.4112421657 -1.4859586139 +12601 52.4107107014 -1.4921829598 +12602 52.409829981 -1.4983003443 +12603 52.408607539 -1.5042584412 +12604 52.4070538323 -1.5100062976 +12605 52.4051821507 -1.5154947736 +12606 52.4030085014 -1.520676964 +12607 52.4005514721 -1.5255086022 +12608 52.3978320702 -1.5299484387 +12609 52.3948735425 -1.5339585949 +12610 52.3917011751 -1.5375048854 +12611 52.388342076 -1.5405571093 +12612 52.3848249429 -1.5430893058 +12613 52.3811798163 -1.5450799728 +12614 52.3774378227 -1.5465122469 +12615 52.3736309076 -1.5473740435 +12616 52.3697915629 -1.5476581549 +12617 52.3659525485 -1.5473623069 +12618 52.3621466133 -1.5464891734 +12619 52.3584062155 -1.545046348 +12620 52.3547632464 -1.5430462749 +12621 52.351248759 -1.5405061376 +12622 52.3478927039 -1.5374477087 +12623 52.3447236748 -1.5338971602 +12624 52.3417686664 -1.5298848382 +12625 52.3390528447 -1.5254450017 +12626 52.3365993346 -1.5206155294 +12627 52.3344290237 -1.5154375968 +12628 52.332560386 -1.5099553259 +12629 52.3310093251 -1.5042154102 +12630 52.3297890406 -1.4982667195 +12631 52.3289099161 -1.4921598862 +12632 52.3283794315 -1.4859468772 +12633 52.3282021004 -1.4796805556 +12634 52.3283794315 -1.4734142339 +12635 52.3289099161 -1.4672012249 +12636 52.3297890406 -1.4610943916 +12637 52.3310093251 -1.4551457009 +12638 52.332560386 -1.4494057852 +12639 52.3344290237 -1.4439235143 +12640 52.3365993346 -1.4387455817 +12641 52.3390528447 -1.4339161094 +12642 52.3417686664 -1.4294762729 +12643 52.3447236748 -1.4254639509 +12644 52.3478927039 -1.4219134024 +12645 52.351248759 -1.4188549735 +12646 52.3547632464 -1.4163148362 +12647 52.3584062155 -1.4143147631 +12648 52.3621466133 -1.4128719377 +12649 52.3659525485 -1.4119988042 +12650 52.3697915629 -1.4117029562 +12651 52.3736309076 -1.4119870676 +12652 52.3774378227 -1.4128488642 +12653 52.3811798163 -1.4142811383 +12654 52.3848249429 -1.4162718053 +12655 52.388342076 -1.4188040018 +12656 52.3917011751 -1.4218562257 +12657 52.3948735425 -1.4254025162 +12658 52.3978320702 -1.4294126724 +12659 52.4005514721 -1.4338525089 +12660 52.4030085014 -1.4386841471 +12661 52.4051821507 -1.4438663375 +12662 52.4070538323 -1.4493548135 +12663 52.408607539 -1.4551026699 +12664 52.409829981 -1.4610607668 +12665 52.4107107014 -1.4671781513 +12666 52.4112421657 -1.4734024973 +12667 52.4114198271 -1.4796805556 +12668 52.3311361111 -1.5373944444 +12669 52.3384789444 -1.52439425 +12670 52.3405328775 -1.5279657452 +12671 52.3427390404 -1.5312866019 +12672 52.3450859722 -1.5343395556 +12673 52.3377472222 -1.5473305556 +12674 52.3311361111 -1.5373944444 +12675 52.4084555556 -1.4218777778 +12676 52.4011283611 -1.4349076111 +12677 52.3990715077 -1.4313348092 +12678 52.3968623818 -1.4280140169 +12679 52.3945125 -1.4249625 +12680 52.4018444444 -1.4119222222 +12681 52.4084555556 -1.4218777778 +12682 52.8727165679 -1.3277777778 +12683 52.8725389176 -1.3341222329 +12684 52.8720074866 -1.3404124051 +12685 52.8711268217 -1.3465944797 +12686 52.8699044571 -1.3526155747 +12687 52.8683508497 -1.3584241967 +12688 52.8664792888 -1.3639706843 +12689 52.8643057815 -1.3692076354 +12690 52.8618489148 -1.3740903145 +12691 52.8591296956 -1.3785770361 +12692 52.8561713699 -1.3826295214 +12693 52.8529992227 -1.3862132249 +12694 52.849640361 -1.3892976278 +12695 52.846123481 -1.391856497 +12696 52.8424786217 -1.3938681056 +12697 52.8387369078 -1.3953154151 +12698 52.8349302827 -1.3961862161 +12699 52.8310912361 -1.396473228 +12700 52.8272525253 -1.3961741563 +12701 52.8234468966 -1.3952917062 +12702 52.8197068054 -1.393833555 +12703 52.8160641401 -1.3918122811 +12704 52.8125499505 -1.3892452525 +12705 52.8091941841 -1.3861544737 +12706 52.8060254317 -1.3825663951 +12707 52.8030706845 -1.3785116842 +12708 52.8003551059 -1.3740249626 +12709 52.7979018179 -1.369144509 +12710 52.7957317053 -1.363911933 +12711 52.7938632398 -1.3583718213 +12712 52.7923123228 -1.3525713588 +12713 52.7910921522 -1.3465599289 +12714 52.79021311 -1.3403886961 +12715 52.7896826753 -1.3341101731 +12716 52.7895053609 -1.3277777778 +12717 52.7896826753 -1.3214453824 +12718 52.79021311 -1.3151668594 +12719 52.7910921522 -1.3089956266 +12720 52.7923123228 -1.3029841968 +12721 52.7938632398 -1.2971837343 +12722 52.7957317053 -1.2916436225 +12723 52.7979018179 -1.2864110466 +12724 52.8003551059 -1.2815305929 +12725 52.8030706845 -1.2770438713 +12726 52.8060254317 -1.2729891605 +12727 52.8091941841 -1.2694010819 +12728 52.8125499505 -1.2663103031 +12729 52.8160641401 -1.2637432744 +12730 52.8197068054 -1.2617220006 +12731 52.8234468966 -1.2602638494 +12732 52.8272525253 -1.2593813993 +12733 52.8310912361 -1.2590823275 +12734 52.8349302827 -1.2593693395 +12735 52.8387369078 -1.2602401405 +12736 52.8424786217 -1.2616874499 +12737 52.846123481 -1.2636990586 +12738 52.849640361 -1.2662579278 +12739 52.8529992227 -1.2693423307 +12740 52.8561713699 -1.2729260341 +12741 52.8591296956 -1.2769785194 +12742 52.8618489148 -1.2814652411 +12743 52.8643057815 -1.2863479202 +12744 52.8664792888 -1.2915848713 +12745 52.8683508497 -1.2971313589 +12746 52.8699044571 -1.3029399809 +12747 52.8711268217 -1.3089610759 +12748 52.8720074866 -1.3151431504 +12749 52.8725389176 -1.3214333226 +12750 52.8727165679 -1.3277777778 +12751 52.824775 -1.4208305556 +12752 52.8252495278 -1.3957835 +12753 52.8282329641 -1.3963064082 +12754 52.8312314664 -1.3964730465 +12755 52.8342294444 -1.3962824722 +12756 52.8337555556 -1.421275 +12757 52.824775 -1.4208305556 +12758 52.8371666667 -1.2346666667 +12759 52.8367260278 -1.2597063611 +12760 52.8337397508 -1.2592174925 +12761 52.8307399007 -1.2590853456 +12762 52.8277420833 -1.2593105556 +12763 52.8281833333 -1.2342138889 +12764 52.8371666667 -1.2346666667 +12765 52.9541172165 -1.08 +12766 52.9539406732 -1.0856666656 +12767 52.9534129191 -1.0912731259 +12768 52.952539561 -1.0967598197 +12769 52.9513298772 -1.1020684668 +12770 52.9497967178 -1.1071426907 +12771 52.9479563679 -1.1119286206 +12772 52.9458283731 -1.1163754663 +12773 52.9434353309 -1.1204360586 +12774 52.9408026494 -1.1240673509 +12775 52.9379582765 -1.1272308755 +12776 52.9349324012 -1.1298931505 +12777 52.9317571331 -1.1320260322 +12778 52.9284661594 -1.1336070103 +12779 52.9250943874 -1.1346194424 +12780 52.9216775732 -1.1350527254 +12781 52.9182519421 -1.1349024025 +12782 52.9148538046 -1.1341702043 +12783 52.9115191711 -1.1328640255 +12784 52.9082833711 -1.1309978346 +12785 52.9051806792 -1.1285915213 +12786 52.902243953 -1.1256706811 +12787 52.8995042861 -1.1222663398 +12788 52.89699068 -1.1184146226 +12789 52.8947297385 -1.1141563688 +12790 52.8927453873 -1.1095366993 +12791 52.8910586221 -1.1046045384 +12792 52.8896872876 -1.0994120974 +12793 52.8886458902 -1.0940143241 +12794 52.8879454451 -1.0884683244 +12795 52.8875933606 -1.0828327612 +12796 52.8875933606 -1.0771672388 +12797 52.8879454451 -1.0715316756 +12798 52.8886458902 -1.0659856759 +12799 52.8896872876 -1.0605879026 +12800 52.8910586221 -1.0553954616 +12801 52.8927453873 -1.0504633007 +12802 52.8947297385 -1.0458436312 +12803 52.89699068 -1.0415853774 +12804 52.8995042861 -1.0377336602 +12805 52.902243953 -1.0343293189 +12806 52.9051806792 -1.0314084787 +12807 52.9082833711 -1.0290021654 +12808 52.9115191711 -1.0271359745 +12809 52.9148538046 -1.0258297957 +12810 52.9182519421 -1.0250975975 +12811 52.9216775732 -1.0249472746 +12812 52.9250943874 -1.0253805576 +12813 52.9284661594 -1.0263929897 +12814 52.9317571331 -1.0279739678 +12815 52.9349324012 -1.0301068495 +12816 52.9379582765 -1.0327691245 +12817 52.9408026494 -1.0359326491 +12818 52.9434353309 -1.0395639414 +12819 52.9458283731 -1.0436245337 +12820 52.9479563679 -1.0480713794 +12821 52.9497967178 -1.0528573093 +12822 52.9513298772 -1.0579315332 +12823 52.952539561 -1.0632401803 +12824 52.9534129191 -1.0687268741 +12825 52.9539406732 -1.0743333344 +12826 52.9541172165 -1.08 +12827 52.8745638889 -1.1075944444 +12828 52.8888314444 -1.09513225 +12829 52.8897890795 -1.0998531952 +12830 52.8910007221 -1.1044119397 +12831 52.8924564722 -1.1087712222 +12832 52.8787666667 -1.120725 +12833 52.8745638889 -1.1075944444 +12834 52.9648666667 -1.0454 +12835 52.9511852778 -1.0573920833 +12836 52.9498260518 -1.0529431955 +12837 52.9482293672 -1.0487162267 +12838 52.9464083333 -1.0447458056 +12839 52.9606666667 -1.0322444444 +12840 52.9648666667 -1.0454 +12841 52.9143111111 -1.1592722222 +12842 52.9149089167 -1.1341868056 +12843 52.9178856696 -1.1348516491 +12844 52.9208865282 -1.1350698583 +12845 52.9238870556 -1.1348395556 +12846 52.9232916667 -1.1598416667 +12847 52.9143111111 -1.1592722222 +12848 52.9270222222 -0.9993333333 +12849 52.9264241111 -1.0257090556 +12850 52.9234437562 -1.0250980782 +12851 52.9204422491 -1.0249341478 +12852 52.9174440278 -1.0252185 +12853 52.9180444444 -0.9987611111 +12854 52.9270222222 -0.9993333333 +12855 52.6410634276 -1.0319444444 +12856 52.6408868765 -1.0375705691 +12857 52.6403590989 -1.0431369207 +12858 52.6394857017 -1.0485843657 +12859 52.6382759635 -1.053855042 +12860 52.6367427346 -1.0588929776 +12861 52.6349023004 -1.0636446878 +12862 52.6327742071 -1.0680597463 +12863 52.6303810526 -1.0720913215 +12864 52.627748246 -1.0756966742 +12865 52.6249037357 -1.0788376114 +12866 52.6218777121 -1.0814808896 +12867 52.6187022857 -1.0835985651 +12868 52.6154111452 -1.085168287 +12869 52.6120391994 -1.08617353 +12870 52.608622206 -1.0866037648 +12871 52.6051963924 -1.0864545645 +12872 52.6017980707 -1.0857276454 +12873 52.5984632535 -1.0844308436 +12874 52.5952272725 -1.082578026 +12875 52.5921244045 -1.0801889387 +12876 52.5891875093 -1.0772889928 +12877 52.5864476827 -1.0739089916 +12878 52.5839339285 -1.0700848014 +12879 52.5816728523 -1.0658569699 +12880 52.5796883817 -1.0612702954 +12881 52.5780015143 -1.0563733535 +12882 52.5766300961 -1.0512179835 +12883 52.5755886349 -1.0458587418 +12884 52.5748881467 -1.0403523279 +12885 52.5745360405 -1.0347569877 +12886 52.5745360405 -1.0291319012 +12887 52.5748881467 -1.023536561 +12888 52.5755886349 -1.0180301471 +12889 52.5766300961 -1.0126709054 +12890 52.5780015143 -1.0075155354 +12891 52.5796883817 -1.0026185935 +12892 52.5816728523 -0.998031919 +12893 52.5839339285 -0.9938040874 +12894 52.5864476827 -0.9899798973 +12895 52.5891875093 -0.9865998961 +12896 52.5921244045 -0.9836999502 +12897 52.5952272725 -0.9813108629 +12898 52.5984632535 -0.9794580453 +12899 52.6017980707 -0.9781612435 +12900 52.6051963924 -0.9774343244 +12901 52.608622206 -0.9772851241 +12902 52.6120391994 -0.9777153589 +12903 52.6154111452 -0.9787206019 +12904 52.6187022857 -0.9802903238 +12905 52.6218777121 -0.9824079993 +12906 52.6249037357 -0.9850512774 +12907 52.627748246 -0.9881922147 +12908 52.6303810526 -0.9917975674 +12909 52.6327742071 -0.9958291425 +12910 52.6349023004 -1.000244201 +12911 52.6367427346 -1.0049959113 +12912 52.6382759635 -1.0100338469 +12913 52.6394857017 -1.0153045232 +12914 52.6403590989 -1.0207519682 +12915 52.6408868765 -1.0263183198 +12916 52.6410634276 -1.0319444444 +12917 52.56495 -1.0683138889 +12918 52.5771455833 -1.0533300833 +12919 52.5784517699 -1.0578004505 +12920 52.5799992746 -1.0620583556 +12921 52.5817753889 -1.0660687778 +12922 52.5703388889 -1.0801166667 +12923 52.56495 -1.0683138889 +12924 52.6458638889 -0.9871722222 +12925 52.6350268889 -1.0005339722 +12926 52.6331813756 -0.9966043647 +12927 52.6311266371 -0.9929662177 +12928 52.6288796111 -0.9896495 +12929 52.640475 -0.97535 +12930 52.6458638889 -0.9871722222 +12931 52.5713138889 -1.0803583333 +12932 52.5806598333 -1.0636405833 +12933 52.5825151294 -1.0675359805 +12934 52.5845772236 -1.0711404251 +12935 52.58682925 -1.0744244167 +12936 52.5779388889 -1.090325 +12937 52.5713138889 -1.0803583333 +12938 52.6407972222 -0.9776805556 +12939 52.6317283056 -0.99396425 +12940 52.6295401098 -0.9905625572 +12941 52.6271736895 -0.9875002128 +12942 52.6246484444 -0.9848022778 +12943 52.6341722222 -0.9677 +12944 52.6407972222 -0.9776805556 +12945 52.6085833333 -1.1130722222 +12946 52.6068874444 -1.0866007222 +12947 52.6098905627 -1.0865119041 +12948 52.6128765769 -1.0859786876 +12949 52.6158211667 -1.0850053333 +12950 52.6175194444 -1.1115138889 +12951 52.6085833333 -1.1130722222 +12952 52.6071416667 -0.950975 +12953 52.6088584167 -0.9772961944 +12954 52.6058550628 -0.9773605349 +12955 52.6028674649 -0.9778692787 +12956 52.5999199444 -0.9788181944 +12957 52.5982055556 -0.9525333333 +12958 52.6071416667 -0.950975 +12959 52.644675 -1.076675 +12960 52.6336289722 -1.0663972778 +12961 52.6354151885 -1.0624252862 +12962 52.6369760432 -1.0582044025 +12963 52.6382987778 -1.0537690556 +12964 52.6490972222 -1.0638138889 +12965 52.644675 -1.076675 +12966 52.5669805556 -0.9875722222 +12967 52.5806593611 -1.0002493889 +12968 52.5790293299 -1.0043947656 +12969 52.5776335702 -1.0087643261 +12970 52.5764834444 -1.0133225 +12971 52.5625555556 -1.0004111111 +12972 52.5669805556 -0.9875722222 +12973 52.6435361111 -1.0777805556 +12974 52.6331404444 -1.0673638056 +12975 52.6349812391 -1.0634615593 +12976 52.6366003276 -1.059302093 +12977 52.6379845 -1.0549193333 +12978 52.6482083333 -1.0651611111 +12979 52.6435361111 -1.0777805556 +12980 52.5681166667 -0.9850805556 +12981 52.5814858611 -0.9984237778 +12982 52.5797529201 -1.0024525214 +12983 52.5782481656 -1.00672106 +12984 52.5769838333 -1.0111946667 +12985 52.5634444444 -0.9976777778 +12986 52.5681166667 -0.9850805556 +12987 52.3393984685 -0.7922222222 +12988 52.3392219097 -0.7978099841 +12989 52.3386941093 -0.8033383821 +12990 52.3378206743 -0.8087486871 +12991 52.3366108832 -0.8139834327 +12992 52.335077587 -0.8189870296 +12993 52.3332370711 -0.8237063586 +12994 52.3311088823 -0.8280913376 +12995 52.3287156191 -0.8320954543 +12996 52.3260826912 -0.8356762609 +12997 52.323238048 -0.8387958239 +12998 52.3202118809 -0.8414211255 +12999 52.3170363014 -0.8435244113 +13000 52.3137449995 -0.8450834812 +13001 52.3103728857 -0.8460819208 +13002 52.3069557192 -0.8465092708 +13003 52.303529729 -0.8463611324 +13004 52.3001312293 -0.8456392083 +13005 52.2967962348 -0.8443512793 +13006 52.293560079 -0.8425111163 +13007 52.290457041 -0.8401383293 +13008 52.2875199827 -0.8372581551 +13009 52.284780002 -0.8339011864 +13010 52.2822661048 -0.8301030446 +13011 52.2800048986 -0.825904001 +13012 52.278020313 -0.8213485493 +13013 52.2763333469 -0.8164849347 +13014 52.2749618482 -0.8113646445 +13015 52.2739203253 -0.806041865 +13016 52.2732197955 -0.800572911 +13017 52.2728676684 -0.7950156334 +13018 52.2728676684 -0.7894288111 +13019 52.2732197955 -0.7838715335 +13020 52.2739203253 -0.7784025794 +13021 52.2749618482 -0.7730797999 +13022 52.2763333469 -0.7679595097 +13023 52.278020313 -0.7630958952 +13024 52.2800048986 -0.7585404435 +13025 52.2822661048 -0.7543413999 +13026 52.284780002 -0.7505432581 +13027 52.2875199827 -0.7471862893 +13028 52.290457041 -0.7443061151 +13029 52.293560079 -0.7419333281 +13030 52.2967962348 -0.7400931651 +13031 52.3001312293 -0.7388052362 +13032 52.303529729 -0.7380833121 +13033 52.3069557192 -0.7379351736 +13034 52.3103728857 -0.7383625236 +13035 52.3137449995 -0.7393609633 +13036 52.3170363014 -0.7409200331 +13037 52.3202118809 -0.7430233189 +13038 52.323238048 -0.7456486206 +13039 52.3260826912 -0.7487681836 +13040 52.3287156191 -0.7523489901 +13041 52.3311088823 -0.7563531068 +13042 52.3332370711 -0.7607380858 +13043 52.335077587 -0.7654574149 +13044 52.3366108832 -0.7704610118 +13045 52.3378206743 -0.7756957574 +13046 52.3386941093 -0.7811060623 +13047 52.3392219097 -0.7866344603 +13048 52.3393984685 -0.7922222222 +13049 52.25975 -0.8188444444 +13050 52.2742679167 -0.8080391111 +13051 52.2752715462 -0.812654855 +13052 52.276526193 -0.8171045318 +13053 52.2780216389 -0.8213519722 +13054 52.2634861111 -0.8321666667 +13055 52.25975 -0.8188444444 +13056 52.3521972222 -0.7660416667 +13057 52.3380003611 -0.7766436667 +13058 52.3370096914 -0.7720147602 +13059 52.3357673179 -0.7675507069 +13060 52.3342833611 -0.7632879167 +13061 52.3484638889 -0.7526944444 +13062 52.3521972222 -0.7660416667 +13063 52.2596388889 -0.817225 +13064 52.2740019167 -0.8065377222 +13065 52.2749240222 -0.8112001893 +13066 52.2761001429 -0.8157083104 +13067 52.2775206944 -0.8200254167 +13068 52.263375 -0.8305472222 +13069 52.2596388889 -0.817225 +13070 52.3506027778 -0.7655472222 +13071 52.3377156111 -0.77516825 +13072 52.3366441745 -0.7705856744 +13073 52.3353238089 -0.7661797483 +13074 52.3337653056 -0.7619864167 +13075 52.3468694444 -0.7522 +13076 52.3506027778 -0.7655472222 +13077 52.2715333333 -0.8469 +13078 52.2808424722 -0.8275625 +13079 52.282902354 -0.8311402354 +13080 52.2851519226 -0.834400312 +13081 52.2875728056 -0.8373160833 +13082 52.2786083333 -0.8559361111 +13083 52.2715333333 -0.8469 +13084 52.3373861111 -0.7336 +13085 52.3285297778 -0.7520706944 +13086 52.3262153965 -0.7489313661 +13087 52.3237366888 -0.7461463395 +13088 52.3211139444 -0.7437383333 +13089 52.3303138889 -0.72455 +13090 52.3373861111 -0.7336 +13091 52.3377472222 -0.8524527778 +13092 52.3271384167 -0.8343298333 +13093 52.3293832458 -0.8310595854 +13094 52.3314378811 -0.8274715192 +13095 52.3332855 -0.8235949444 +13096 52.3442416667 -0.8423083333 +13097 52.3377472222 -0.8524527778 +13098 52.2771305556 -0.7279055556 +13099 52.2880981667 -0.7465651944 +13100 52.2856446324 -0.7494051076 +13101 52.2833582938 -0.7525943514 +13102 52.2812578056 -0.7561068611 +13103 52.2706361111 -0.7380333333 +13104 52.2771305556 -0.7279055556 +13105 52.1055109067 -0.6166666667 +13106 52.105334342 -0.6222251498 +13107 52.1048065238 -0.6277245811 +13108 52.1039330593 -0.6331065404 +13109 52.1027232271 -0.6383138633 +13110 52.1011898783 -0.6432912525 +13111 52.0993492989 -0.6479858678 +13112 52.0972210357 -0.6523478896 +13113 52.0948276879 -0.6563310496 +13114 52.0921946656 -0.659893122 +13115 52.089349919 -0.6629963717 +13116 52.0863236401 -0.6656079531 +13117 52.0831479414 -0.6677002562 +13118 52.0798565142 -0.6692511961 +13119 52.0764842696 -0.670244443 +13120 52.0730669685 -0.6706695909 +13121 52.0696408411 -0.6705222627 +13122 52.0662422032 -0.6698041505 +13123 52.0629070708 -0.6685229932 +13124 52.0596707793 -0.6666924882 +13125 52.0565676093 -0.6643321417 +13126 52.0536304244 -0.6614670575 +13127 52.0508903241 -0.6581276674 +13128 52.0483763159 -0.6543494062 +13129 52.0461150089 -0.6501723341 +13130 52.044130334 -0.6456407123 +13131 52.0424432914 -0.6408025339 +13132 52.04107173 -0.6357090174 +13133 52.0400301594 -0.6304140667 +13134 52.0393295974 -0.6249737029 +13135 52.0389774541 -0.6194454757 +13136 52.0389774541 -0.6138878577 +13137 52.0393295974 -0.6083596304 +13138 52.0400301594 -0.6029192666 +13139 52.04107173 -0.5976243159 +13140 52.0424432914 -0.5925307995 +13141 52.044130334 -0.5876926211 +13142 52.0461150089 -0.5831609992 +13143 52.0483763159 -0.5789839272 +13144 52.0508903241 -0.5752056659 +13145 52.0536304244 -0.5718662758 +13146 52.0565676093 -0.5690011916 +13147 52.0596707793 -0.5666408451 +13148 52.0629070708 -0.5648103401 +13149 52.0662422032 -0.5635291828 +13150 52.0696408411 -0.5628110707 +13151 52.0730669685 -0.5626637424 +13152 52.0764842696 -0.5630888903 +13153 52.0798565142 -0.5640821372 +13154 52.0831479414 -0.5656330771 +13155 52.0863236401 -0.5677253802 +13156 52.089349919 -0.5703369616 +13157 52.0921946656 -0.5734402114 +13158 52.0948276879 -0.5770022838 +13159 52.0972210357 -0.5809854437 +13160 52.0993492989 -0.5853474656 +13161 52.1011898783 -0.5900420809 +13162 52.1027232271 -0.59501947 +13163 52.1039330593 -0.6002267929 +13164 52.1048065238 -0.6056087522 +13165 52.105334342 -0.6111081835 +13166 52.1055109067 -0.6166666667 +13167 52.0262083333 -0.6541416667 +13168 52.0417852222 -0.6385356667 +13169 52.0431237873 -0.6428961638 +13170 52.0446991176 -0.6470435365 +13171 52.0464984167 -0.6509440556 +13172 52.0309361111 -0.6665305556 +13173 52.0262083333 -0.6541416667 +13174 52.11955 -0.5776055556 +13175 52.1026172778 -0.5946302778 +13176 52.1012692712 -0.5902709864 +13177 52.0996846029 -0.5861270565 +13178 52.0978761944 -0.5822322778 +13179 52.1148222222 -0.5651888889 +13180 52.11955 -0.5776055556 +13181 52.996266979 -0.5603222222 +13182 52.9960904368 -0.565994404 +13183 52.9955626858 -0.5716063218 +13184 52.994689333 -0.577098356 +13185 52.9934796564 -0.5824121696 +13186 52.9919465064 -0.5874913311 +13187 52.9901061679 -0.5922819171 +13188 52.9879781863 -0.5967330879 +13189 52.9855851591 -0.6007976284 +13190 52.9829524945 -0.6044324502 +13191 52.9801081399 -0.6075990482 +13192 52.9770822846 -0.6102639079 +13193 52.9739070377 -0.6123988586 +13194 52.9706160864 -0.6139813683 +13195 52.9672443378 -0.6149947786 +13196 52.9638275476 -0.6154284763 +13197 52.9604019412 -0.6152780005 +13198 52.9570038284 -0.6145450841 +13199 52.9536692196 -0.6132376293 +13200 52.950433444 -0.6113696187 +13201 52.9473307757 -0.6089609616 +13202 52.9443940723 -0.6060372784 +13203 52.9416544268 -0.6026296253 +13204 52.9391408407 -0.5987741625 +13205 52.9368799173 -0.5945117694 +13206 52.9348955822 -0.5898876105 +13207 52.9332088307 -0.5849506575 +13208 52.9318375075 -0.5797531725 +13209 52.9307961187 -0.5743501564 +13210 52.9300956793 -0.5687987704 +13211 52.9297435978 -0.5631577344 +13212 52.9297435978 -0.5574867101 +13213 52.9300956793 -0.551845674 +13214 52.9307961187 -0.546294288 +13215 52.9318375075 -0.540891272 +13216 52.9332088307 -0.5356937869 +13217 52.9348955822 -0.530756834 +13218 52.9368799173 -0.526132675 +13219 52.9391408407 -0.5218702819 +13220 52.9416544268 -0.5180148192 +13221 52.9443940723 -0.5146071661 +13222 52.9473307757 -0.5116834828 +13223 52.950433444 -0.5092748257 +13224 52.9536692196 -0.5074068151 +13225 52.9570038284 -0.5060993604 +13226 52.9604019412 -0.5053664439 +13227 52.9638275476 -0.5052159682 +13228 52.9672443378 -0.5056496659 +13229 52.9706160864 -0.5066630762 +13230 52.9739070377 -0.5082455858 +13231 52.9770822846 -0.5103805365 +13232 52.9801081399 -0.5130453963 +13233 52.9829524945 -0.5162119943 +13234 52.9855851591 -0.519846816 +13235 52.9879781863 -0.5239113565 +13236 52.9901061679 -0.5283625273 +13237 52.9919465064 -0.5331531134 +13238 52.9934796564 -0.5382322748 +13239 52.994689333 -0.5435460884 +13240 52.9955626858 -0.5490381227 +13241 52.9960904368 -0.5546500404 +13242 52.996266979 -0.5603222222 +13243 52.931293 -0.6285518889 +13244 52.9414361667 -0.6023251944 +13245 52.9438101274 -0.6053708766 +13246 52.9463402205 -0.6080502032 +13247 52.9490058611 -0.6103413333 +13248 52.9388649167 -0.6365603611 +13249 52.931293 -0.6285518889 +13250 52.9953680278 -0.4901250278 +13251 52.9845253889 -0.51829125 +13252 52.9821499092 -0.5152459863 +13253 52.979618365 -0.5125682452 +13254 52.9769513889 -0.5102798056 +13255 52.9877961667 -0.4821061111 +13256 52.9953680278 -0.4901250278 +13257 52.9655111111 -0.6465194444 +13258 52.9613583333 -0.6153789167 +13259 52.964387462 -0.6153974861 +13260 52.9674050634 -0.6149598521 +13261 52.9703861389 -0.6140695278 +13262 52.9742833333 -0.6432944444 +13263 52.9655111111 -0.6465194444 +13264 52.9526333333 -0.4816833333 +13265 52.9559658056 -0.5064422778 +13266 52.9530372713 -0.5077235244 +13267 52.9501911894 -0.509440117 +13268 52.9474511111 -0.51157775 +13269 52.9438611111 -0.4849027778 +13270 52.9526333333 -0.4816833333 +13271 53.0101906944 -0.5665701111 +13272 52.9961111667 -0.5656517222 +13273 52.9962663366 -0.5606649345 +13274 52.9961485956 -0.5556753315 +13275 52.9957589167 -0.5507238889 +13276 53.0105427222 -0.5516831111 +13277 53.0101906944 -0.5665701111 +13278 52.9136083333 -0.54540575 +13279 52.9307613889 -0.5465145 +13280 52.9301394272 -0.5513929375 +13281 52.9297863492 -0.5563443631 +13282 52.9297050556 -0.5613283056 +13283 52.9132563056 -0.5602594722 +13284 52.9136083333 -0.54540575 +13285 52.6546625512 -0.4759055556 +13286 52.6544848957 -0.4822183994 +13287 52.6539534489 -0.4884772319 +13288 52.6530727579 -0.4946285077 +13289 52.6518503568 -0.5006196095 +13290 52.6502967026 -0.5063993013 +13291 52.6484250848 -0.5119181697 +13292 52.6462515105 -0.5171290496 +13293 52.6437945672 -0.5219874283 +13294 52.6410752618 -0.5264518282 +13295 52.6381168408 -0.5304841609 +13296 52.6349445897 -0.5340500523 +13297 52.631585616 -0.5371191351 +13298 52.6280686166 -0.5396653057 +13299 52.6244236311 -0.5416669443 +13300 52.6206817852 -0.5431070957 +13301 52.6168750233 -0.5439736099 +13302 52.6130358359 -0.5442592411 +13303 52.6091969817 -0.5439617044 +13304 52.6053912083 -0.54308369 +13305 52.6016509723 -0.5416328355 +13306 52.5980081635 -0.5396216554 +13307 52.5944938332 -0.5370674297 +13308 52.5911379304 -0.5339920525 +13309 52.5879690473 -0.5304218419 +13310 52.5850141767 -0.5263873122 +13311 52.5822984832 -0.5219229123 +13312 52.5798450902 -0.5170667305 +13313 52.5776748839 -0.5118601699 +13314 52.575806337 -0.5063475957 +13315 52.574255352 -0.5005759591 +13316 52.5730351276 -0.4945943989 +13317 52.5721560465 -0.4884538261 +13318 52.5716255882 -0.4822064938 +13319 52.5714482659 -0.4759055556 +13320 52.5716255882 -0.4696046173 +13321 52.5721560465 -0.463357285 +13322 52.5730351276 -0.4572167122 +13323 52.574255352 -0.451235152 +13324 52.575806337 -0.4454635154 +13325 52.5776748839 -0.4399509412 +13326 52.5798450902 -0.4347443806 +13327 52.5822984832 -0.4298881989 +13328 52.5850141767 -0.4254237989 +13329 52.5879690473 -0.4213892692 +13330 52.5911379304 -0.4178190586 +13331 52.5944938332 -0.4147436814 +13332 52.5980081635 -0.4121894557 +13333 52.6016509723 -0.4101782756 +13334 52.6053912083 -0.4087274211 +13335 52.6091969817 -0.4078494068 +13336 52.6130358359 -0.40755187 +13337 52.6168750233 -0.4078375012 +13338 52.6206817852 -0.4087040154 +13339 52.6244236311 -0.4101441668 +13340 52.6280686166 -0.4121458054 +13341 52.631585616 -0.414691976 +13342 52.6349445897 -0.4177610588 +13343 52.6381168408 -0.4213269502 +13344 52.6410752618 -0.4253592829 +13345 52.6437945672 -0.4298236828 +13346 52.6462515105 -0.4346820616 +13347 52.6484250848 -0.4398929414 +13348 52.6502967026 -0.4454118098 +13349 52.6518503568 -0.4511915016 +13350 52.6530727579 -0.4571826034 +13351 52.6539534489 -0.4633338792 +13352 52.6544848957 -0.4695927117 +13353 52.6546625512 -0.4759055556 +13354 52.5921861111 -0.5636166667 +13355 52.5967718611 -0.5387953333 +13356 52.5995733524 -0.5405613037 +13357 52.6024450404 -0.5419912752 +13358 52.605372 -0.54307775 +13359 52.6007888889 -0.5678833333 +13360 52.5921861111 -0.5636166667 +13361 52.6338611111 -0.3881305556 +13362 52.6293098333 -0.4129719444 +13363 52.6265062386 -0.4112122551 +13364 52.6236327327 -0.409789456 +13365 52.6207042778 -0.4087108889 +13366 52.6252583333 -0.3838527778 +13367 52.6338611111 -0.3881305556 +13368 52.1199552691 -0.3186111111 +13369 52.1197787048 -0.3241713908 +13370 52.1192508877 -0.3296725996 +13371 52.118377425 -0.3350562982 +13372 52.1171675954 -0.3402653038 +13373 52.1156342498 -0.3452443011 +13374 52.1137936743 -0.3499404329 +13375 52.1116654157 -0.3543038634 +13376 52.1092720731 -0.3582883093 +13377 52.1066390567 -0.3618515313 +13378 52.1037943165 -0.364955782 +13379 52.1007680445 -0.3675682054 +13380 52.0975923532 -0.3696611824 +13381 52.0943009337 -0.3712126211 +13382 52.0909286972 -0.3722061867 +13383 52.0875114044 -0.3726314698 +13384 52.0840852855 -0.3724840918 +13385 52.0806866562 -0.3717657458 +13386 52.0773515323 -0.3704841729 +13387 52.0741152492 -0.3686530753 +13388 52.0710120873 -0.3662919654 +13389 52.0680749102 -0.3634259553 +13390 52.0653348174 -0.3600854865 +13391 52.062820816 -0.3563060054 +13392 52.0605595152 -0.3521275851 +13393 52.0585748458 -0.347594501 +13394 52.056887808 -0.3427547618 +13395 52.0555162505 -0.3376596025 +13396 52.0544746828 -0.3323629441 +13397 52.0537741228 -0.326920826 +13398 52.0534219804 -0.3213908161 +13399 52.0534219804 -0.3158314061 +13400 52.0537741228 -0.3103013962 +13401 52.0544746828 -0.3048592781 +13402 52.0555162505 -0.2995626198 +13403 52.056887808 -0.2944674604 +13404 52.0585748458 -0.2896277212 +13405 52.0605595152 -0.2850946371 +13406 52.062820816 -0.2809162168 +13407 52.0653348174 -0.2771367357 +13408 52.0680749102 -0.273796267 +13409 52.0710120873 -0.2709302568 +13410 52.0741152492 -0.2685691469 +13411 52.0773515323 -0.2667380493 +13412 52.0806866562 -0.2654564765 +13413 52.0840852855 -0.2647381305 +13414 52.0875114044 -0.2645907525 +13415 52.0909286972 -0.2650160355 +13416 52.0943009337 -0.2660096011 +13417 52.0975923532 -0.2675610398 +13418 52.1007680445 -0.2696540168 +13419 52.1037943165 -0.2722664402 +13420 52.1066390567 -0.2753706909 +13421 52.1092720731 -0.2789339129 +13422 52.1116654157 -0.2829183588 +13423 52.1137936743 -0.2872817893 +13424 52.1156342498 -0.2919779211 +13425 52.1171675954 -0.2969569184 +13426 52.118377425 -0.302165924 +13427 52.1192508877 -0.3075496226 +13428 52.1197787048 -0.3130508314 +13429 52.1199552691 -0.3186111111 +13430 52.0421166667 -0.3446666667 +13431 52.0549213889 -0.3348690556 +13432 52.0559533739 -0.3394451207 +13433 52.057235281 -0.3438518961 +13434 52.0587566944 -0.3480535556 +13435 52.0459527778 -0.3578472222 +13436 52.0421166667 -0.3446666667 +13437 52.1314555556 -0.2923277778 +13438 52.1184116944 -0.3023411667 +13439 52.11737904 -0.2977597768 +13440 52.1160962173 -0.2933484744 +13441 52.1145736944 -0.2891432222 +13442 52.1276194444 -0.279125 +13443 52.1314555556 -0.2923277778 +13444 52.0382166667 -0.3476277778 +13445 52.0549188611 -0.3348561389 +13446 52.0559501295 -0.339432504 +13447 52.0572313152 -0.3438396998 +13448 52.0587520278 -0.3480418889 +13449 52.0420527778 -0.3608055556 +13450 52.0382166667 -0.3476277778 +13451 52.1314611111 -0.2923444444 +13452 52.1184141389 -0.3023537222 +13453 52.1173818267 -0.2977706736 +13454 52.1160992039 -0.2933577082 +13455 52.1145767222 -0.2891508333 +13456 52.127625 -0.2791361111 +13457 52.1314611111 -0.2923444444 +13458 52.5013558845 -0.2509305556 +13459 52.5011793299 -0.2565388288 +13460 52.5006515417 -0.2620875194 +13461 52.499778127 -0.2675176819 +13462 52.4985683643 -0.2727716385 +13463 52.4970351043 -0.2777935952 +13464 52.4951946324 -0.2825302375 +13465 52.4930664948 -0.286931299 +13466 52.4906732901 -0.2909500969 +13467 52.4880404274 -0.2945440276 +13468 52.4851958556 -0.2976750187 +13469 52.4821697656 -0.3003099319 +13470 52.4789942684 -0.3024209115 +13471 52.4757030532 -0.3039856767 +13472 52.4723310297 -0.3049877539 +13473 52.4689139562 -0.3054166464 +13474 52.4654880608 -0.3052679403 +13475 52.4620896568 -0.3045433456 +13476 52.4587547575 -0.3032506726 +13477 52.4555186956 -0.3014037436 +13478 52.4524157489 -0.2990222414 +13479 52.4494787782 -0.2961314959 +13480 52.4467388803 -0.2927622124 +13481 52.4442250598 -0.2889501434 +13482 52.4419639235 -0.2847357077 +13483 52.4399793997 -0.2801635622 +13484 52.4382924865 -0.2752821285 +13485 52.4369210311 -0.2701430821 +13486 52.4358795413 -0.2648008074 +13487 52.4351790338 -0.2593118247 +13488 52.434826918 -0.2537341961 +13489 52.434826918 -0.248126915 +13490 52.4351790338 -0.2425492865 +13491 52.4358795413 -0.2370603038 +13492 52.4369210311 -0.231718029 +13493 52.4382924865 -0.2265789826 +13494 52.4399793997 -0.221697549 +13495 52.4419639235 -0.2171254034 +13496 52.4442250598 -0.2129109677 +13497 52.4467388803 -0.2090988987 +13498 52.4494787782 -0.2057296152 +13499 52.4524157489 -0.2028388697 +13500 52.4555186956 -0.2004573675 +13501 52.4587547575 -0.1986104385 +13502 52.4620896568 -0.1973177656 +13503 52.4654880608 -0.1965931708 +13504 52.4689139562 -0.1964444647 +13505 52.4723310297 -0.1968733572 +13506 52.4757030532 -0.1978754344 +13507 52.4789942684 -0.1994401997 +13508 52.4821697656 -0.2015511792 +13509 52.4851958556 -0.2041860924 +13510 52.4880404274 -0.2073170836 +13511 52.4906732901 -0.2109110142 +13512 52.4930664948 -0.2149298121 +13513 52.4951946324 -0.2193308736 +13514 52.4970351043 -0.2240675159 +13515 52.4985683643 -0.2290894726 +13516 52.499778127 -0.2343434292 +13517 52.5006515417 -0.2397735918 +13518 52.5011793299 -0.2453222823 +13519 52.5013558845 -0.2509305556 +13520 52.4673944444 -0.3321527778 +13521 52.4661358889 -0.3053404444 +13522 52.4691397138 -0.3054061395 +13523 52.4721349212 -0.3050281085 +13524 52.4750971111 -0.3042093333 +13525 52.4763555556 -0.3310083333 +13526 52.4673944444 -0.3321527778 +13527 52.4687722222 -0.1714472222 +13528 52.4699780556 -0.1965159444 +13529 52.4669748648 -0.1964576045 +13530 52.4639806853 -0.1968427065 +13531 52.4610198889 -0.1976680278 +13532 52.4598138889 -0.1725861111 +13533 52.4687722222 -0.1714472222 +13534 52.7727293506 -0.0298666667 +13535 52.7725528028 -0.0355097506 +13536 52.7720250351 -0.0410928807 +13537 52.7711516544 -0.0465567445 +13538 52.769941939 -0.051843305 +13539 52.7684087394 -0.0568964209 +13540 52.7665683408 -0.0616624461 +13541 52.7644402889 -0.0660908021 +13542 52.7620471818 -0.0701345158 +13543 52.7594144279 -0.0737507198 +13544 52.7565699754 -0.076901106 +13545 52.7535440143 -0.0795523311 +13546 52.7503686545 -0.0816763678 +13547 52.7470775843 -0.0832507985 +13548 52.7437057116 -0.084259049 +13549 52.7402887937 -0.084690559 +13550 52.7368630569 -0.0845408891 +13551 52.7334648127 -0.0838117617 +13552 52.7301300729 -0.0825110373 +13553 52.726894168 -0.0806526253 +13554 52.7237913741 -0.078256332 +13555 52.7208545501 -0.0753476454 +13556 52.7181147907 -0.0719574621 +13557 52.7156010987 -0.0681217567 +13558 52.7133400792 -0.0638811987 +13559 52.7113556589 -0.0592807215 +13560 52.7096688344 -0.0543690465 +13561 52.7082974515 -0.0491981686 +13562 52.7072560171 -0.0438228081 +13563 52.706555547 -0.0382998343 +13564 52.70620345 -0.0326876677 +13565 52.70620345 -0.0270456657 +13566 52.706555547 -0.021433499 +13567 52.7072560171 -0.0159105253 +13568 52.7082974515 -0.0105351647 +13569 52.7096688344 -0.0053642868 +13570 52.7113556589 -0.0004526119 +13571 52.7133400792 0.0041478653 +13572 52.7156010987 0.0083884233 +13573 52.7181147907 0.0122241288 +13574 52.7208545501 0.0156143121 +13575 52.7237913741 0.0185229986 +13576 52.726894168 0.020919292 +13577 52.7301300729 0.0227777039 +13578 52.7334648127 0.0240784284 +13579 52.7368630569 0.0248075558 +13580 52.7402887937 0.0249572257 +13581 52.7437057116 0.0245257156 +13582 52.7470775843 0.0235174651 +13583 52.7503686545 0.0219430344 +13584 52.7535440143 0.0198189978 +13585 52.7565699754 0.0171677727 +13586 52.7594144279 0.0140173865 +13587 52.7620471818 0.0104011825 +13588 52.7644402889 0.0063574687 +13589 52.7665683408 0.0019291128 +13590 52.7684087394 -0.0028369125 +13591 52.769941939 -0.0078900283 +13592 52.7711516544 -0.0131765888 +13593 52.7720250351 -0.0186404526 +13594 52.7725528028 -0.0242235827 +13595 52.7727293506 -0.0298666667 +13596 52.7863611111 -0.03605 +13597 52.7724917222 -0.0364105278 +13598 52.7727151248 -0.0314710385 +13599 52.7726673154 -0.0265184494 +13600 52.7723486944 -0.0215931944 +13601 52.7862166667 -0.0212277778 +13602 52.7863611111 -0.03605 +13603 52.6916888889 -0.0237138889 +13604 52.7063969722 -0.0233277778 +13605 52.7061736718 -0.0282594659 +13606 52.7062211083 -0.0332042095 +13607 52.7065389167 -0.0381218333 +13608 52.6918305556 -0.0385027778 +13609 52.6916888889 -0.0237138889 +13610 52.123808025 0.1315027778 +13611 52.1236314608 0.1259420186 +13612 52.123103644 0.1204403355 +13613 52.1222301818 0.1150561727 +13614 52.1210203528 0.109846718 +13615 52.1194870082 0.1048672915 +13616 52.1176464337 0.1001707551 +13617 52.1155181763 0.0958069486 +13618 52.1131248351 0.0918221595 +13619 52.1104918203 0.0882586307 +13620 52.1076470817 0.0851541128 +13621 52.1046208116 0.0825414648 +13622 52.1014451223 0.0804483079 +13623 52.0981537048 0.0788967361 +13624 52.0947814705 0.0779030855 +13625 52.0913641799 0.0774777663 +13626 52.0879380633 0.0776251576 +13627 52.0845394362 0.078343566 +13628 52.0812043146 0.0796252498 +13629 52.0779680338 0.0814565055 +13630 52.0748648741 0.0838178192 +13631 52.0719276991 0.0866840764 +13632 52.0691876082 0.090024833 +13633 52.0666736086 0.0938046397 +13634 52.0644123095 0.0979834198 +13635 52.0624276416 0.1025168941 +13636 52.060740605 0.1073570499 +13637 52.0593690485 0.1124526477 +13638 52.0583274817 0.1177497618 +13639 52.0576269221 0.1231923481 +13640 52.0572747801 0.1287228336 +13641 52.0572747801 0.1342827219 +13642 52.0576269221 0.1398132075 +13643 52.0583274817 0.1452557938 +13644 52.0593690485 0.1505529079 +13645 52.060740605 0.1556485057 +13646 52.0624276416 0.1604886614 +13647 52.0644123095 0.1650221357 +13648 52.0666736086 0.1692009158 +13649 52.0691876082 0.1729807226 +13650 52.0719276991 0.1763214791 +13651 52.0748648741 0.1791877364 +13652 52.0779680338 0.18154905 +13653 52.0812043146 0.1833803058 +13654 52.0845394362 0.1846619895 +13655 52.0879380633 0.1853803979 +13656 52.0913641799 0.1855277892 +13657 52.0947814705 0.1851024701 +13658 52.0981537048 0.1841088195 +13659 52.1014451223 0.1825572476 +13660 52.1046208116 0.1804640907 +13661 52.1076470817 0.1778514427 +13662 52.1104918203 0.1747469248 +13663 52.1131248351 0.1711833961 +13664 52.1155181763 0.167198607 +13665 52.1176464337 0.1628348005 +13666 52.1194870082 0.158138264 +13667 52.1210203528 0.1531588375 +13668 52.1222301818 0.1479493829 +13669 52.123103644 0.1425652201 +13670 52.1236314608 0.137063537 +13671 52.123808025 0.1315027778 +13672 52.0616638889 0.0662027778 +13673 52.0702925556 0.0885908611 +13674 52.0727600356 0.0858030761 +13675 52.075372398 0.0833876371 +13676 52.0781083611 0.0813643056 +13677 52.0692888889 0.0584833333 +13678 52.0616638889 0.0662027778 +13679 52.1210833333 0.1931527778 +13680 52.1128239167 0.1716298056 +13681 52.1105024373 0.1747339861 +13682 52.1080179068 0.177484965 +13683 52.1053906111 0.1798603056 +13684 52.1134583333 0.2008861111 +13685 52.1210833333 0.1931527778 +13686 52.0594518333 0.06455875 +13687 52.0692389444 0.0899554167 +13688 52.0716326258 0.0870104264 +13689 52.0741801083 0.0844272855 +13690 52.0768606667 0.0822270556 +13691 52.0670756667 0.0568375833 +13692 52.0594518333 0.06455875 +13693 52.1210931389 0.1973161944 +13694 52.1117941389 0.1730776667 +13695 52.1093989495 0.1760220254 +13696 52.1068500334 0.1786034196 +13697 52.1041681667 0.1808008611 +13698 52.1134693889 0.2050466944 +13699 52.1210931389 0.1973161944 +13700 52.2466098839 0.175 +13701 52.2464322185 0.1687452292 +13702 52.2459007422 0.1625439707 +13703 52.2450200018 0.1564492751 +13704 52.2437975319 0.1505132739 +13705 52.2422437896 0.1447867299 +13706 52.2403720645 0.1393186007 +13707 52.2381983642 0.1341556167 +13708 52.2357412764 0.1293418805 +13709 52.2330218089 0.1249184884 +13710 52.2300632087 0.1209231787 +13711 52.2268907621 0.1173900105 +13712 52.2235315779 0.1143490731 +13713 52.2200143539 0.111826232 +13714 52.2163691314 0.1098429104 +13715 52.2126270374 0.10841591 +13716 52.2088200185 0.1075572719 +13717 52.2049805669 0.1072741782 +13718 52.2011414438 0.1075688958 +13719 52.1973353987 0.108438762 +13720 52.1935948911 0.1098762123 +13721 52.1899518133 0.1118688498 +13722 52.1864372194 0.1143995555 +13723 52.1830810609 0.1174466383 +13724 52.179911933 0.1209840236 +13725 52.176956831 0.1249814783 +13726 52.1742409224 0.1294048705 +13727 52.1717873329 0.1342164617 +13728 52.1696169512 0.1393752286 +13729 52.1677482519 0.1448372124 +13730 52.1661971396 0.1505558918 +13731 52.1649768144 0.1564825772 +13732 52.1640976604 0.1625668229 +13733 52.163567158 0.1687568532 +13734 52.163389821 0.175 +13735 52.163567158 0.1812431468 +13736 52.1640976604 0.1874331771 +13737 52.1649768144 0.1935174228 +13738 52.1661971396 0.1994441082 +13739 52.1677482519 0.2051627876 +13740 52.1696169512 0.2106247714 +13741 52.1717873329 0.2157835383 +13742 52.1742409224 0.2205951295 +13743 52.176956831 0.2250185217 +13744 52.179911933 0.2290159764 +13745 52.1830810609 0.2325533617 +13746 52.1864372194 0.2356004445 +13747 52.1899518133 0.2381311502 +13748 52.1935948911 0.2401237877 +13749 52.1973353987 0.241561238 +13750 52.2011414438 0.2424311042 +13751 52.2049805669 0.2427258218 +13752 52.2088200185 0.2424427281 +13753 52.2126270374 0.24158409 +13754 52.2163691314 0.2401570896 +13755 52.2200143539 0.238173768 +13756 52.2235315779 0.2356509269 +13757 52.2268907621 0.2326099895 +13758 52.2300632087 0.2290768213 +13759 52.2330218089 0.2250815116 +13760 52.2357412764 0.2206581195 +13761 52.2381983642 0.2158443833 +13762 52.2403720645 0.2106813993 +13763 52.2422437896 0.2052132701 +13764 52.2437975319 0.1994867261 +13765 52.2450200018 0.1935507249 +13766 52.2459007422 0.1874560293 +13767 52.2464322185 0.1812547708 +13768 52.2466098839 0.175 +13769 52.1682055556 0.1152138889 +13770 52.1749323889 0.1281993889 +13771 52.1770828876 0.1247950609 +13772 52.1793785446 0.1216513551 +13773 52.1818074444 0.1187846389 +13774 52.1750833333 0.1058055556 +13775 52.1682055556 0.1152138889 +13776 52.2422222222 0.2357 +13777 52.23506925 0.2218291389 +13778 52.2329176763 0.2252353881 +13779 52.2306208904 0.2283799158 +13780 52.2281908611 0.2312463889 +13781 52.2353472222 0.245125 +13782 52.2422222222 0.2357 +13783 52.1707 0.1243861111 +13784 52.1737569444 0.13028475 +13785 52.1758197269 0.1267348617 +13786 52.1780344549 0.1234358833 +13787 52.1803896111 0.120405 +13788 52.177575 0.114975 +13789 52.1707 0.1243861111 +13790 52.2406555556 0.2369527778 +13791 52.2338656944 0.2237949167 +13792 52.2316275242 0.2270582421 +13793 52.2292505454 0.2300497493 +13794 52.2267471667 0.2327538611 +13795 52.2337777778 0.2463805556 +13796 52.2406555556 0.2369527778 +13797 52.4035421051 0.4864055556 +13798 52.4033644435 0.4801286155 +13799 52.4028329786 0.4739053782 +13800 52.4019522573 0.4677890832 +13801 52.4007298139 0.4618320474 +13802 52.3991761056 0.4560852143 +13803 52.3973044218 0.4505977154 +13804 52.3951307702 0.4454164473 +13805 52.3926737381 0.4405856688 +13806 52.389954333 0.4361466219 +13807 52.3869958019 0.4321371786 +13808 52.3838234307 0.4285915182 +13809 52.3804643276 0.4255398363 +13810 52.3769471901 0.423008089 +13811 52.3733020589 0.4210177748 +13812 52.3695600605 0.4195857539 +13813 52.3657531405 0.4187241089 +13814 52.3619137907 0.4184400464 +13815 52.3580747711 0.4187358401 +13816 52.3542688306 0.4196088168 +13817 52.3505284275 0.421051384 +13818 52.3468854532 0.4230511001 +13819 52.3433709608 0.4255907844 +13820 52.3400149007 0.4286486685 +13821 52.336845867 0.4321985849 +13822 52.333890854 0.436210193 +13823 52.3311750281 0.4406492399 +13824 52.3287215143 0.4454778536 +13825 52.3265512 0.4506548658 +13826 52.3246825593 0.4561361626 +13827 52.323131496 0.4618750585 +13828 52.3219112096 0.4678226925 +13829 52.3210320836 0.4739284412 +13830 52.3205015982 0.4801403467 +13831 52.3203242668 0.4864055556 +13832 52.3205015982 0.4926707644 +13833 52.3210320836 0.4988826699 +13834 52.3219112096 0.5049884186 +13835 52.323131496 0.5109360526 +13836 52.3246825593 0.5166749486 +13837 52.3265512 0.5221562453 +13838 52.3287215143 0.5273332576 +13839 52.3311750281 0.5321618712 +13840 52.333890854 0.5366009181 +13841 52.336845867 0.5406125262 +13842 52.3400149007 0.5441624426 +13843 52.3433709608 0.5472203267 +13844 52.3468854532 0.5497600111 +13845 52.3505284275 0.5517597271 +13846 52.3542688306 0.5532022944 +13847 52.3580747711 0.554075271 +13848 52.3619137907 0.5543710647 +13849 52.3657531405 0.5540870022 +13850 52.3695600605 0.5532253572 +13851 52.3733020589 0.5517933363 +13852 52.3769471901 0.5498030221 +13853 52.3804643276 0.5472712748 +13854 52.3838234307 0.5442195929 +13855 52.3869958019 0.5406739325 +13856 52.389954333 0.5366644892 +13857 52.3926737381 0.5322254424 +13858 52.3951307702 0.5273946639 +13859 52.3973044218 0.5222133957 +13860 52.3991761056 0.5167258968 +13861 52.4007298139 0.5109790637 +13862 52.4019522573 0.5050220279 +13863 52.4028329786 0.4989057329 +13864 52.4033644435 0.4926824956 +13865 52.4035421051 0.4864055556 +13866 52.3707543333 0.39318525 +13867 52.3670513611 0.41895225 +13868 52.3700143536 0.4197280497 +13869 52.3729354022 0.420850861 +13870 52.3757993056 0.4223148889 +13871 52.3795009722 0.39655725 +13872 52.3707543333 0.39318525 +13873 52.3530635 0.5795797222 +13874 52.3567994722 0.5538478611 +13875 52.3538371034 0.5530659598 +13876 52.3509169327 0.5519375386 +13877 52.3480541389 0.5504685278 +13878 52.3443168611 0.5762097222 +13879 52.3530635 0.5795797222 +13880 52.6899400798 0.5505555556 +13881 52.6897624251 0.5442376252 +13882 52.6892309809 0.5379737499 +13883 52.6883502941 0.5318175182 +13884 52.6871278989 0.5258215902 +13885 52.6855742523 0.5200372433 +13886 52.6837026437 0.5145139307 +13887 52.6815290804 0.5092988557 +13888 52.6790721494 0.5044365668 +13889 52.676352858 0.4999685751 +13890 52.6733944524 0.4959329997 +13891 52.6702222182 0.4923642421 +13892 52.6668632627 0.4892926942 +13893 52.6633462825 0.4867444802 +13894 52.6597013175 0.4847412373 +13895 52.655959493 0.4832999341 +13896 52.6521527532 0.4824327301 +13897 52.6483135886 0.4821468767 +13898 52.6444747577 0.4824446604 +13899 52.6406690077 0.4833233885 +13900 52.6369287951 0.4847754171 +13901 52.6332860095 0.4867882214 +13902 52.629771702 0.4893445072 +13903 52.6264158213 0.4924223626 +13904 52.6232469594 0.4959954484 +13905 52.6202921087 0.5000332254 +13906 52.6175764338 0.5045012171 +13907 52.6151230578 0.5093613045 +13908 52.6129528667 0.5145720512 +13909 52.6110843329 0.5200890564 +13910 52.609533359 0.5258653315 +13911 52.6083131433 0.531851698 +13912 52.6074340684 0.5379972043 +13913 52.606903614 0.5442495556 +13914 52.606726293 0.5505555556 +13915 52.606903614 0.5568615556 +13916 52.6074340684 0.5631139068 +13917 52.6083131433 0.5692594131 +13918 52.609533359 0.5752457796 +13919 52.6110843329 0.5810220547 +13920 52.6129528667 0.5865390599 +13921 52.6151230578 0.5917498066 +13922 52.6175764338 0.596609894 +13923 52.6202921087 0.6010778857 +13924 52.6232469594 0.6051156627 +13925 52.6264158213 0.6086887485 +13926 52.629771702 0.6117666039 +13927 52.6332860095 0.6143228897 +13928 52.6369287951 0.616335694 +13929 52.6406690077 0.6177877226 +13930 52.6444747577 0.6186664507 +13931 52.6483135886 0.6189642344 +13932 52.6521527532 0.618678381 +13933 52.655959493 0.617811177 +13934 52.6597013175 0.6163698738 +13935 52.6633462825 0.6143666309 +13936 52.6668632627 0.611818417 +13937 52.6702222182 0.608746869 +13938 52.6733944524 0.6051781114 +13939 52.676352858 0.601142536 +13940 52.6790721494 0.5966745443 +13941 52.6815290804 0.5918122554 +13942 52.6837026437 0.5865971804 +13943 52.6855742523 0.5810738678 +13944 52.6871278989 0.5752895209 +13945 52.6883502941 0.5692935929 +13946 52.6892309809 0.5631373613 +13947 52.6897624251 0.5568734859 +13948 52.6899400798 0.5505555556 +13949 52.5939194444 0.5520111111 +13950 52.6068224167 0.5552008333 +13951 52.6067267341 0.5502455031 +13952 52.6068497766 0.5452918019 +13953 52.6071909167 0.5403657222 +13954 52.5952555556 0.5374194444 +13955 52.5939194444 0.5520111111 +13956 52.7000972222 0.5633555556 +13957 52.6894784167 0.5607228889 +13958 52.6889216802 0.5656053044 +13959 52.6881511361 0.5704082912 +13960 52.6871708333 0.5751065 +13961 52.6987583333 0.5779833333 +13962 52.7000972222 0.5633555556 +13963 52.6119888889 0.476925 +13964 52.6211635 0.4987624167 +13965 52.6235043234 0.4956781358 +13966 52.6259742675 0.4928787707 +13967 52.6285605 0.4903788889 +13968 52.6193888889 0.46855 +13969 52.6119888889 0.476925 +13970 52.6845638889 0.6240777778 +13971 52.6754983333 0.6023875 +13972 52.6731559687 0.6054717452 +13973 52.6706845186 0.6082699432 +13974 52.6680968611 0.6107675833 +13975 52.6771666667 0.6324694444 +13976 52.6845638889 0.6240777778 +13977 52.4510112135 0.5610111111 +13978 52.450833553 0.5547274249 +13979 52.4503020916 0.5484974994 +13980 52.449421376 0.5423746316 +13981 52.4481989406 0.5364111949 +13982 52.4466452426 0.5306581878 +13983 52.4447735713 0.5251647946 +13984 52.4425999343 0.5199779625 +13985 52.440142919 0.515141998 +13986 52.4374235329 0.5106981874 +13987 52.4344650226 0.5066844433 +13988 52.4312926741 0.5031349815 +13989 52.4279335955 0.5000800299 +13990 52.4244164841 0.4975455726 +13991 52.4207713805 0.4955531305 +13992 52.417029411 0.4941195818 +13993 52.4132225209 0.4932570219 +13994 52.4093832018 0.4929726646 +13995 52.4055442135 0.4932687858 +13996 52.4017383046 0.494142709 +13997 52.3979979332 0.4955868334 +13998 52.3943549902 0.4975887035 +13999 52.3908405284 0.5001311201 +14000 52.3874844981 0.5031922911 +14001 52.3843154928 0.5067460207 +14002 52.3813605068 0.5107619357 +14003 52.3786447059 0.5152057463 +14004 52.3761912149 0.52003954 +14005 52.3740209211 0.5252221043 +14006 52.3721522981 0.530709278 +14007 52.3706012496 0.5364543259 +14008 52.3693809749 0.5424083345 +14009 52.3685018574 0.5485206266 +14010 52.3679713771 0.5547391888 +14011 52.3677940475 0.5610111111 +14012 52.3679713771 0.5672830334 +14013 52.3685018574 0.5735015956 +14014 52.3693809749 0.5796138877 +14015 52.3706012496 0.5855678964 +14016 52.3721522981 0.5913129442 +14017 52.3740209211 0.5968001179 +14018 52.3761912149 0.6019826822 +14019 52.3786447059 0.6068164759 +14020 52.3813605068 0.6112602866 +14021 52.3843154928 0.6152762015 +14022 52.3874844981 0.6188299311 +14023 52.3908405284 0.6218911021 +14024 52.3943549902 0.6244335187 +14025 52.3979979332 0.6264353888 +14026 52.4017383046 0.6278795132 +14027 52.4055442135 0.6287534364 +14028 52.4093832018 0.6290495576 +14029 52.4132225209 0.6287652003 +14030 52.417029411 0.6279026404 +14031 52.4207713805 0.6264690917 +14032 52.4244164841 0.6244766497 +14033 52.4279335955 0.6219421923 +14034 52.4312926741 0.6188872407 +14035 52.4344650226 0.615337779 +14036 52.4374235329 0.6113240349 +14037 52.440142919 0.6068802242 +14038 52.4425999343 0.6020442597 +14039 52.4447735713 0.5968574276 +14040 52.4466452426 0.5913640344 +14041 52.4481989406 0.5856110273 +14042 52.449421376 0.5796475906 +14043 52.4503020916 0.5735247228 +14044 52.450833553 0.5672947973 +14045 52.4510112135 0.5610111111 +14046 52.3733966389 0.4878663333 +14047 52.3823689722 0.5093056111 +14048 52.3847182231 0.5062544483 +14049 52.3871958535 0.5034876038 +14050 52.389789 0.5010195 +14051 52.3808191667 0.4795878056 +14052 52.3733966389 0.4878663333 +14053 52.4453773611 0.6342404722 +14054 52.4364317778 0.6127547778 +14055 52.4340808663 0.6158060476 +14056 52.4316015868 0.6185718298 +14057 52.4290068611 0.6210377778 +14058 52.4379549167 0.6425311111 +14059 52.4453773611 0.6342404722 +14060 52.1686382148 0.9554138889 +14061 52.1684605475 0.9491700573 +14062 52.1679290655 0.9429796439 +14063 52.1670483157 0.9368956062 +14064 52.1658258326 0.9309699841 +14065 52.1642720733 0.9252534516 +14066 52.1624003276 0.91979488 +14067 52.1602266031 0.9146409182 +14068 52.1577694876 0.9098355913 +14069 52.155049989 0.9054199238 +14070 52.1520913543 0.9014315882 +14071 52.1489188703 0.8979045841 +14072 52.1455596457 0.8948689485 +14073 52.1420423786 0.8923505021 +14074 52.1383971107 0.8903706309 +14075 52.1346549692 0.8889461079 +14076 52.130847901 0.8880889535 +14077 52.1270083989 0.887806338 +14078 52.1231692242 0.8881005247 +14079 52.1193631272 0.8889688561 +14080 52.1156225676 0.8904037816 +14081 52.1119794383 0.8923929263 +14082 52.1084647939 0.8949192016 +14083 52.1051085866 0.8979609547 +14084 52.1019394118 0.9014921567 +14085 52.0989842656 0.9054826276 +14086 52.0962683158 0.9098982951 +14087 52.0938146888 0.9147014867 +14088 52.0916442735 0.9198512507 +14089 52.0897755451 0.9253037047 +14090 52.0882244085 0.9310124084 +14091 52.087004064 0.9369287569 +14092 52.0861248961 0.9430023922 +14093 52.0855943853 0.9491816284 +14094 52.0854170454 0.9554138889 +14095 52.0855943853 0.9616461494 +14096 52.0861248961 0.9678253856 +14097 52.087004064 0.9738990208 +14098 52.0882244085 0.9798153694 +14099 52.0897755451 0.9855240731 +14100 52.0916442735 0.9909765271 +14101 52.0938146888 0.996126291 +14102 52.0962683158 1.0009294826 +14103 52.0989842656 1.0053451502 +14104 52.1019394118 1.0093356211 +14105 52.1051085866 1.0128668231 +14106 52.1084647939 1.0159085762 +14107 52.1119794383 1.0184348515 +14108 52.1156225676 1.0204239962 +14109 52.1193631272 1.0218589216 +14110 52.1231692242 1.0227272531 +14111 52.1270083989 1.0230214398 +14112 52.130847901 1.0227388243 +14113 52.1346549692 1.0218816699 +14114 52.1383971107 1.0204571469 +14115 52.1420423786 1.0184772757 +14116 52.1455596457 1.0159588292 +14117 52.1489188703 1.0129231937 +14118 52.1520913543 1.0093961896 +14119 52.155049989 1.005407854 +14120 52.1577694876 1.0009921865 +14121 52.1602266031 0.9961868596 +14122 52.1624003276 0.9910328978 +14123 52.1642720733 0.9855743262 +14124 52.1658258326 0.9798577937 +14125 52.1670483157 0.9739321716 +14126 52.1679290655 0.9678481339 +14127 52.1684605475 0.9616577205 +14128 52.1686382148 0.9554138889 +14129 52.0870821389 0.8945785833 +14130 52.09594825 0.9104756667 +14131 52.0980224587 0.9069544023 +14132 52.1002474723 0.9036846797 +14133 52.10261175 0.9006835278 +14134 52.0937486944 0.8847938611 +14135 52.0870821389 0.8945785833 +14136 52.1677814167 1.0178328056 +14137 52.1581005278 1.0003954167 +14138 52.1560243877 1.0039183892 +14139 52.1537973789 1.0071885817 +14140 52.1514311111 1.010189 +14141 52.1611149444 1.0276337778 +14142 52.1677814167 1.0178328056 +14143 52.5308612731 1.0520222222 +14144 52.5306847192 1.0464101911 +14145 52.5301569332 1.0408577828 +14146 52.5292835223 1.0354239821 +14147 52.5280737648 1.0301665059 +14148 52.5265405113 1.0251411855 +14149 52.5247000473 1.0204013713 +14150 52.5225719192 1.0159973633 +14151 52.5201787251 1.0119758757 +14152 52.5175458742 1.0083795406 +14153 52.5147013154 1.0052464557 +14154 52.5116752395 1.0026097816 +14155 52.5084997572 1.0004973925 +14156 52.5052085578 0.9989315839 +14157 52.5018365507 0.9979288402 +14158 52.4984194941 0.9974996651 +14159 52.494993616 0.9976484753 +14160 52.4915952294 0.9983735593 +14161 52.4882603475 0.9996671014 +14162 52.4850243027 1.00151527 +14163 52.4819213726 1.0038983689 +14164 52.4789844178 1.0067910512 +14165 52.476244535 1.0101625908 +14166 52.4737307285 1.0139772115 +14167 52.4714696049 1.0181944671 +14168 52.4694850923 1.0227696711 +14169 52.4677981888 1.0276543694 +14170 52.4664267412 1.032796852 +14171 52.4653852575 1.0381426984 +14172 52.4646847541 1.0436353506 +14173 52.4643326403 1.0492167076 +14174 52.4643326403 1.0548277368 +14175 52.4646847541 1.0604090939 +14176 52.4653852575 1.065901746 +14177 52.4664267412 1.0712475924 +14178 52.4677981888 1.0763900751 +14179 52.4694850923 1.0812747734 +14180 52.4714696049 1.0858499774 +14181 52.4737307285 1.090067233 +14182 52.476244535 1.0938818536 +14183 52.4789844178 1.0972533933 +14184 52.4819213726 1.1001460755 +14185 52.4850243027 1.1025291745 +14186 52.4882603475 1.104377343 +14187 52.4915952294 1.1056708852 +14188 52.494993616 1.1063959692 +14189 52.4984194941 1.1065447793 +14190 52.5018365507 1.1061156042 +14191 52.5052085578 1.1051128606 +14192 52.5084997572 1.1035470519 +14193 52.5116752395 1.1014346628 +14194 52.5147013154 1.0987979888 +14195 52.5175458742 1.0956649038 +14196 52.5201787251 1.0920685687 +14197 52.5225719192 1.0880470812 +14198 52.5247000473 1.0836430731 +14199 52.5265405113 1.0789032589 +14200 52.5280737648 1.0738779385 +14201 52.5292835223 1.0686204623 +14202 52.5301569332 1.0631866617 +14203 52.5306847192 1.0576342533 +14204 52.5308612731 1.0520222222 +14205 52.4542777778 1.0331583333 +14206 52.4651658333 1.0395878889 +14207 52.4659820364 1.0348536529 +14208 52.4670554677 1.0302589954 +14209 52.4683773889 1.0258412778 +14210 52.4573277778 1.0193194444 +14211 52.4542777778 1.0331583333 +14212 52.5449833333 1.0711527778 +14213 52.5302505833 1.0624254444 +14214 52.5295449608 1.0672134848 +14215 52.5285787725 1.0718775255 +14216 52.5273598889 1.0763795 +14217 52.5419333333 1.0850166667 +14218 52.5449833333 1.0711527778 +14219 52.4727333333 0.9833472222 +14220 52.4793926667 1.0063476944 +14221 52.4819797884 1.003847467 +14222 52.4846939569 1.0017391739 +14223 52.4875130833 1.0000400278 +14224 52.4808583333 0.9770555556 +14225 52.4727333333 0.9833472222 +14226 52.5223555556 1.1207472222 +14227 52.5157296667 1.0977450556 +14228 52.5131402516 1.1002399859 +14229 52.5104241196 1.1023418593 +14230 52.5076034167 1.1040336389 +14231 52.5142333333 1.12705 +14232 52.5223555556 1.1207472222 +14233 52.4744638889 0.9878055556 +14234 52.4797591944 1.0059615 +14235 52.4823666245 1.0035164819 +14236 52.485097998 1.0014662454 +14237 52.4879310833 0.9998275556 +14238 52.4825777778 0.9814722222 +14239 52.4744638889 0.9878055556 +14240 52.5228194444 1.1198027778 +14241 52.5162530833 1.0971755833 +14242 52.5136926291 1.0997504044 +14243 52.5110009461 1.1019361107 +14244 52.5081999722 1.1037149444 +14245 52.5147083333 1.1261416667 +14246 52.5228194444 1.1198027778 +14247 52.7175398849 1.2826638889 +14248 52.7173622309 1.2763419716 +14249 52.7168307887 1.2700741436 +14250 52.7159501052 1.2639140275 +14251 52.7147277146 1.2579143166 +14252 52.713174074 1.252126321 +14253 52.7113024726 1.2465995249 +14254 52.7091289177 1.2413811617 +14255 52.7066719965 1.236515808 +14256 52.703952716 1.232045001 +14257 52.7009943225 1.2280068838 +14258 52.6978221014 1.2244358797 +14259 52.6944631601 1.2213623995 +14260 52.6909461951 1.218812584 +14261 52.687301246 1.2168080836 +14262 52.6835594382 1.2153658776 +14263 52.6797527158 1.2144981329 +14264 52.675913569 1.2142121053 +14265 52.6720747562 1.2145100826 +14266 52.6682690245 1.2153893702 +14267 52.6645288303 1.216842319 +14268 52.6608860629 1.2188563964 +14269 52.6573717732 1.2214142969 +14270 52.6540159098 1.2244940948 +14271 52.6508470644 1.2280694342 +14272 52.6478922294 1.2321097566 +14273 52.645176569 1.2365805636 +14274 52.6427232063 1.2414437122 +14275 52.6405530271 1.2466577401 +14276 52.6386845036 1.2521782185 +14277 52.6371335382 1.2579581291 +14278 52.6359133293 1.263948263 +14279 52.6350342594 1.2700976362 +14280 52.634503808 1.2763539214 +14281 52.6343264879 1.2826638889 +14282 52.634503808 1.2889738564 +14283 52.6350342594 1.2952301415 +14284 52.6359133293 1.3013795148 +14285 52.6371335382 1.3073696486 +14286 52.6386845036 1.3131495593 +14287 52.6405530271 1.3186700377 +14288 52.6427232063 1.3238840656 +14289 52.645176569 1.3287472142 +14290 52.6478922294 1.3332180212 +14291 52.6508470644 1.3372583436 +14292 52.6540159098 1.3408336829 +14293 52.6573717732 1.3439134809 +14294 52.6608860629 1.3464713814 +14295 52.6645288303 1.3484854587 +14296 52.6682690245 1.3499384076 +14297 52.6720747562 1.3508176951 +14298 52.675913569 1.3511156725 +14299 52.6797527158 1.3508296449 +14300 52.6835594382 1.3499619002 +14301 52.687301246 1.3485196942 +14302 52.6909461951 1.3465151938 +14303 52.6944631601 1.3439653783 +14304 52.6978221014 1.3408918981 +14305 52.7009943225 1.337320894 +14306 52.703952716 1.3332827768 +14307 52.7066719965 1.3288119698 +14308 52.7091289177 1.323946616 +14309 52.7113024726 1.3187282529 +14310 52.713174074 1.3132014568 +14311 52.7147277146 1.3074134611 +14312 52.7159501052 1.3014137503 +14313 52.7168307887 1.2952536342 +14314 52.7173622309 1.2889858062 +14315 52.7175398849 1.2826638889 +14316 52.6707472222 1.1952277778 +14317 52.6709072222 1.2147172778 +14318 52.6738970556 1.2142956962 +14319 52.6768975825 1.2142297104 +14320 52.6798931944 1.2145197222 +14321 52.6797333333 1.1950472222 +14322 52.6707472222 1.1952277778 +14323 52.6810555556 1.3700972222 +14324 52.68092125 1.3506258889 +14325 52.6779309394 1.3510383033 +14326 52.6749303384 1.3510950081 +14327 52.6719350556 1.3507957778 +14328 52.6720694444 1.3702833333 +14329 52.6810555556 1.3700972222 +14330 52.8448400548 -2.4070333333 +14331 52.8446635088 -2.4126857617 +14332 52.8441357465 -2.4182781367 +14333 52.8432623748 -2.4237510472 +14334 52.842052672 -2.4290463597 +14335 52.8405194884 -2.4341078399 +14336 52.8386791092 -2.4388817526 +14337 52.83655108 -2.4433174353 +14338 52.8341579987 -2.4473678374 +14339 52.8315252736 -2.4509900203 +14340 52.8286808528 -2.4541456127 +14341 52.8256549258 -2.4568012165 +14342 52.8224796025 -2.4589287581 +14343 52.8191885707 -2.4605057833 +14344 52.815816738 -2.4615156908 +14345 52.8123998614 -2.4619479035 +14346 52.8089741667 -2.4617979748 +14347 52.8055759649 -2.4610676306 +14348 52.8022412674 -2.4597647448 +14349 52.7990054042 -2.4579032504 +14350 52.7959026509 -2.4555029865 +14351 52.7929658657 -2.452589484 +14352 52.7902261431 -2.4491936904 +14353 52.7877124853 -2.4453516401 +14354 52.7854514968 -2.4411040699 +14355 52.783467104 -2.4364959876 +14356 52.781780303 -2.4315761948 +14357 52.7804089394 -2.4263967722 +14358 52.7793675197 -2.4210125304 +14359 52.7786670595 -2.4154804323 +14360 52.7783149675 -2.4098589945 +14361 52.7783149675 -2.4042076722 +14362 52.7786670595 -2.3985862344 +14363 52.7793675197 -2.3930541363 +14364 52.7804089394 -2.3876698944 +14365 52.781780303 -2.3824904719 +14366 52.783467104 -2.3775706791 +14367 52.7854514968 -2.3729625967 +14368 52.7877124853 -2.3687150266 +14369 52.7902261431 -2.3648729763 +14370 52.7929658657 -2.3614771827 +14371 52.7959026509 -2.3585636801 +14372 52.7990054042 -2.3561634163 +14373 52.8022412674 -2.3543019219 +14374 52.8055759649 -2.3529990361 +14375 52.8089741667 -2.3522686919 +14376 52.8123998614 -2.3521187632 +14377 52.815816738 -2.3525509758 +14378 52.8191885707 -2.3535608834 +14379 52.8224796025 -2.3551379086 +14380 52.8256549258 -2.3572654502 +14381 52.8286808528 -2.359921054 +14382 52.8315252736 -2.3630766464 +14383 52.8341579987 -2.3666988293 +14384 52.83655108 -2.3707492314 +14385 52.8386791092 -2.3751849141 +14386 52.8405194884 -2.3799588268 +14387 52.842052672 -2.385020307 +14388 52.8432623748 -2.3903156195 +14389 52.8441357465 -2.39578853 +14390 52.8446635088 -2.4013809049 +14391 52.8448400548 -2.4070333333 +14392 52.3766204797 0.78 +14393 52.376443922 0.7744075413 +14394 52.3759161243 0.7688744967 +14395 52.375042694 0.7634596447 +14396 52.3738329095 0.7582205001 +14397 52.3722996215 0.7532126991 +14398 52.3704591158 0.7484894056 +14399 52.3683309388 0.7441007439 +14400 52.3659376891 0.7400932655 +14401 52.3633047762 0.7365094537 +14402 52.3604601494 0.7333872738 +14403 52.357434 0.7307597713 +14404 52.3542584394 0.7286547238 +14405 52.3509671575 0.7270943498 +14406 52.3475950644 0.7260950772 +14407 52.3441779193 0.7256673739 +14408 52.3407519509 0.7258156423 +14409 52.3373534732 0.726538178 +14410 52.3340185006 0.7278271932 +14411 52.3307823664 0.7296689055 +14412 52.3276793494 0.7320436881 +14413 52.3247423112 0.734926283 +14414 52.3220023496 0.7382860716 +14415 52.31948847 0.7420874025 +14416 52.3172272799 0.7462899707 +14417 52.3152427085 0.750849245 +14418 52.3135557546 0.7557169399 +14419 52.3121842658 0.7608415249 +14420 52.3111427505 0.7661687685 +14421 52.3104422259 0.7716423088 +14422 52.3100901013 0.7772042465 +14423 52.3100901013 0.7827957535 +14424 52.3104422259 0.7883576912 +14425 52.3111427505 0.7938312315 +14426 52.3121842658 0.7991584751 +14427 52.3135557546 0.8042830601 +14428 52.3152427085 0.809150755 +14429 52.3172272799 0.8137100293 +14430 52.31948847 0.8179125975 +14431 52.3220023496 0.8217139284 +14432 52.3247423112 0.825073717 +14433 52.3276793494 0.8279563119 +14434 52.3307823664 0.8303310945 +14435 52.3340185006 0.8321728068 +14436 52.3373534732 0.833461822 +14437 52.3407519509 0.8341843577 +14438 52.3441779193 0.8343326261 +14439 52.3475950644 0.8339049228 +14440 52.3509671575 0.8329056502 +14441 52.3542584394 0.8313452762 +14442 52.357434 0.8292402287 +14443 52.3604601494 0.8266127262 +14444 52.3633047762 0.8234905463 +14445 52.3659376891 0.8199067345 +14446 52.3683309388 0.8158992561 +14447 52.3704591158 0.8115105944 +14448 52.3722996215 0.8067873009 +14449 52.3738329095 0.8017794999 +14450 52.375042694 0.7965403553 +14451 52.3759161243 0.7911255033 +14452 52.376443922 0.7855924587 +14453 52.3766204797 0.78 +14454 52.3296939722 0.6818130278 +14455 52.3340415556 0.7278162222 +14456 52.3369605969 0.7266595214 +14457 52.3399316222 0.7259369978 +14458 52.3429304444 0.7256546111 +14459 52.3385770556 0.6795900833 +14460 52.3296939722 0.6818130278 +14461 52.3559142222 0.8642396389 +14462 52.3529141111 0.8320553889 +14463 52.3500010766 0.8332521006 +14464 52.3470338347 0.8340149861 +14465 52.3440365556 0.8343379167 +14466 52.3470311667 0.8664634722 +14467 52.3559142222 0.8642396389 +14468 52.1445194444 -0.4699694444 +14469 52.1431472222 -0.4754777778 +14470 52.1376055556 -0.4778222222 +14471 52.1351944444 -0.473425 +14472 52.1345444444 -0.4660722222 +14473 52.1395611111 -0.4620055556 +14474 52.1431944444 -0.4655805556 +14475 52.1445194444 -0.4699694444 +14476 52.4983111111 -1.9406583333 +14477 52.4955527778 -1.9467111111 +14478 52.4879805556 -1.9424222222 +14479 52.4882194444 -1.9326861111 +14480 52.4903972222 -1.9296444444 +14481 52.4954916667 -1.9297361111 +14482 52.4976833333 -1.9314527778 +14483 52.4983111111 -1.9406583333 +14484 52.763725 1.3413777778 +14485 52.7589055556 1.3352138889 +14486 52.7531694444 1.3470583333 +14487 52.7601555556 1.3564444444 +14488 52.7643277778 1.3476527778 +14489 52.763725 1.3413777778 +14490 52.876175 -1.7855305556 +14491 52.8737777778 -1.7896972222 +14492 52.869925 -1.7901194444 +14493 52.8639833333 -1.7803777778 +14494 52.8708833333 -1.7689 +14495 52.8761416667 -1.7776138889 +14496 52.876175 -1.7855305556 +14497 52.8857111111 -2.2413305556 +14498 52.8818361111 -2.2480138889 +14499 52.878175 -2.2509111111 +14500 52.8730916667 -2.2458916667 +14501 52.8733055556 -2.2392972222 +14502 52.8802388889 -2.23105 +14503 52.8857111111 -2.2413305556 +14504 52.6548 -2.1215583333 +14505 52.6446611111 -2.1211027778 +14506 52.6406138889 -2.1161916667 +14507 52.6392138889 -2.1026027778 +14508 52.6469722222 -2.0985861111 +14509 52.6564722222 -2.1064611111 +14510 52.6548 -2.1215583333 +14511 52.290975 -0.6910527778 +14512 52.2872861111 -0.7013305556 +14513 52.2828583333 -0.7012527778 +14514 52.2791583333 -0.6947 +14515 52.279475 -0.6839666667 +14516 52.2861777778 -0.6817027778 +14517 52.2908 -0.6836805556 +14518 52.290975 -0.6910527778 +14519 52.5918888889 -1.1498138889 +14520 52.5795416667 -1.1565666667 +14521 52.5774944444 -1.1481777778 +14522 52.5785861111 -1.1375694444 +14523 52.5911527778 -1.136575 +14524 52.5918888889 -1.1498138889 +14525 52.8869805556 -1.733425 +14526 52.8769722222 -1.732525 +14527 52.8770083333 -1.7205361111 +14528 52.8840833333 -1.715675 +14529 52.8872555556 -1.7236166667 +14530 52.8869805556 -1.733425 +14531 52.5010833333 -0.964475 +14532 52.4957944444 -0.9705583333 +14533 52.4890361111 -0.9670111111 +14534 52.49195 -0.9521666667 +14535 52.4998388889 -0.9539333333 +14536 52.5010833333 -0.964475 +14537 52.3309666667 -1.9904305556 +14538 52.3249638889 -1.9966583333 +14539 52.3214833333 -1.9934444444 +14540 52.3197611111 -1.9885444444 +14541 52.3198361111 -1.9815083333 +14542 52.3262611111 -1.9757583333 +14543 52.3309666667 -1.9904305556 +14544 52.1464944444 0.5095194444 +14545 52.1393277778 0.5008166667 +14546 52.1304 0.5051555556 +14547 52.1337222222 0.5260694444 +14548 52.1459222222 0.5192861111 +14549 52.1464944444 0.5095194444 +14550 52.6320527778 -1.1321138889 +14551 52.63035 -1.1391555556 +14552 52.6250333333 -1.1383638889 +14553 52.6224777778 -1.1312555556 +14554 52.6244472222 -1.126375 +14555 52.6289055556 -1.1232083333 +14556 52.6320527778 -1.1321138889 +14557 52.2851944444 -0.3211638889 +14558 52.2799638889 -0.3232416667 +14559 52.2757138889 -0.3221722222 +14560 52.2740583333 -0.31275 +14561 52.2770305556 -0.3047 +14562 52.2820888889 -0.3030472222 +14563 52.2849 -0.3065888889 +14564 52.2851944444 -0.3211638889 +14565 52.1137055556 -1.8592277778 +14566 52.1045055556 -1.8661638889 +14567 52.1024805556 -1.8485638889 +14568 52.1118416667 -1.8427472222 +14569 52.1137055556 -1.8592277778 +14570 52.643425 1.3143916667 +14571 52.6392277778 1.306325 +14572 52.6312888889 1.3124305556 +14573 52.6298722222 1.315325 +14574 52.6334861111 1.3273166667 +14575 52.6363027778 1.3273055556 +14576 52.6439222222 1.3208805556 +14577 52.643425 1.3143916667 +14578 52.9892694444 -1.1597333333 +14579 52.9873611111 -1.1628611111 +14580 52.9847805556 -1.1632805556 +14581 52.9799111111 -1.1615972222 +14582 52.9804916667 -1.1516527778 +14583 52.9822333333 -1.1467583333 +14584 52.9902666667 -1.1490861111 +14585 52.9892694444 -1.1597333333 +14586 52.5912555556 -0.2647388889 +14587 52.5888777778 -0.2671416667 +14588 52.5848972222 -0.2673222222 +14589 52.5826527778 -0.2662805556 +14590 52.5809666667 -0.259575 +14591 52.5831861111 -0.2503805556 +14592 52.5931027778 -0.2566833333 +14593 52.5912555556 -0.2647388889 +14594 52.3345611111 -1.2492583333 +14595 52.3334 -1.2535833333 +14596 52.3222833333 -1.2598194444 +14597 52.3219944444 -1.24855 +14598 52.3234916667 -1.2393027778 +14599 52.3268305556 -1.2349888889 +14600 52.3299555556 -1.2354277778 +14601 52.3322388889 -1.2369777778 +14602 52.3347111111 -1.2430083333 +14603 52.3345611111 -1.2492583333 +14604 52.8149555556 -2.1262083333 +14605 52.8056 -2.1221472222 +14606 52.8076833333 -2.1107027778 +14607 52.811475 -2.1095888889 +14608 52.8170972222 -2.1118638889 +14609 52.8149555556 -2.1262083333 +14610 52.7534361111 -0.5802055556 +14611 52.75105 -0.5877777778 +14612 52.7468638889 -0.5882805556 +14613 52.7445277778 -0.5872194444 +14614 52.7414027778 -0.5816472222 +14615 52.7427916667 -0.5750555556 +14616 52.74725 -0.5675138889 +14617 52.7535111111 -0.570525 +14618 52.7534361111 -0.5802055556 +14619 52.8752055556 -2.5272138889 +14620 52.8644888889 -2.5324694444 +14621 52.8617055556 -2.5165222222 +14622 52.865825 -2.5145416667 +14623 52.8672861111 -2.5119222222 +14624 52.871175 -2.5124138889 +14625 52.8752555556 -2.5187416667 +14626 52.8734138889 -2.5219416667 +14627 52.8752055556 -2.5272138889 +14628 52.6599611111 -1.8045694444 +14629 52.6529083333 -1.8159944444 +14630 52.6490972222 -1.8095166667 +14631 52.6468833333 -1.8028055556 +14632 52.6522055556 -1.794625 +14633 52.6558527778 -1.7946388889 +14634 52.6599611111 -1.8045694444 +14635 52.0655388889 1.4600444444 +14636 52.0590805556 1.449675 +14637 52.0519277778 1.4574888889 +14638 52.0552388889 1.4692555556 +14639 52.0596166667 1.4700805556 +14640 52.0655388889 1.4600444444 +14641 52.5603666667 0.8507277778 +14642 52.5535222222 0.8488444444 +14643 52.5489833333 0.85245 +14644 52.5489666667 0.8659805556 +14645 52.5603555556 0.86615 +14646 52.5603666667 0.8507277778 +14647 52.9525027778 -0.9219444444 +14648 52.9438333333 -0.9229722222 +14649 52.9426555556 -0.900525 +14650 52.94975 -0.9016 +14651 52.9528916667 -0.9076666667 +14652 52.9522305556 -0.9117305556 +14653 52.9525027778 -0.9219444444 +14654 52.5791083333 0.0698444444 +14655 52.5693833333 0.0748722222 +14656 52.5725166667 0.0908222222 +14657 52.5822833333 0.0857444444 +14658 52.5791083333 0.0698444444 +14659 52.0203222222 -0.807125 +14660 52.0155555556 -0.8203583333 +14661 52.0057194444 -0.8106138889 +14662 52.0106333333 -0.7978666667 +14663 52.0203222222 -0.807125 +14664 53.2897691896 -4.5353333333 +14665 53.2895915492 -4.5417394023 +14666 53.2890601481 -4.5480906587 +14667 53.2881795327 -4.5543327631 +14668 53.2869572374 -4.5604123179 +14669 53.2854037189 -4.5662773276 +14670 53.2835322662 -4.5718776474 +14671 53.281358886 -4.5771654137 +14672 53.2789021651 -4.5820954562 +14673 53.2761831096 -4.5866256844 +14674 53.273224965 -4.5907174486 +14675 53.2700530154 -4.5943358686 +14676 53.2666943668 -4.597450131 +14677 53.2631777142 -4.6000337501 +14678 53.2595330952 -4.6020647903 +14679 53.2557916327 -4.6035260505 +14680 53.2519852685 -4.6044052057 +14681 53.2481464901 -4.604694908 +14682 53.2443080527 -4.6043928434 +14683 53.2405027001 -4.6035017468 +14684 53.2367628853 -4.6020293729 +14685 53.2331204938 -4.599988425 +14686 53.2296065728 -4.5973964418 +14687 53.2262510669 -4.5942756435 +14688 53.2230825641 -4.5906527385 +14689 53.2201280529 -4.5865586931 +14690 53.2174126938 -4.5820284648 +14691 53.2149596063 -4.5771007037 +14692 53.2127896729 -4.5718174223 +14693 53.2109213629 -4.5662236383 +14694 53.209370576 -4.5603669927 +14695 53.2081505083 -4.5542973456 +14696 53.2072715406 -4.548066355 +14697 53.2067411509 -4.5417270399 +14698 53.2065638516 -4.5353333333 +14699 53.2067411509 -4.5289396267 +14700 53.2072715406 -4.5226003117 +14701 53.2081505083 -4.5163693211 +14702 53.209370576 -4.510299674 +14703 53.2109213629 -4.5044430283 +14704 53.2127896729 -4.4988492444 +14705 53.2149596063 -4.493565963 +14706 53.2174126938 -4.4886382018 +14707 53.2201280529 -4.4841079736 +14708 53.2230825641 -4.4800139281 +14709 53.2262510669 -4.4763910232 +14710 53.2296065728 -4.4732702249 +14711 53.2331204938 -4.4706782417 +14712 53.2367628853 -4.4686372938 +14713 53.2405027001 -4.4671649199 +14714 53.2443080527 -4.4662738233 +14715 53.2481464901 -4.4659717587 +14716 53.2519852685 -4.4662614609 +14717 53.2557916327 -4.4671406162 +14718 53.2595330952 -4.4686018763 +14719 53.2631777142 -4.4706329166 +14720 53.2666943668 -4.4732165356 +14721 53.2700530154 -4.4763307981 +14722 53.273224965 -4.4799492181 +14723 53.2761831096 -4.4840409822 +14724 53.2789021651 -4.4885712105 +14725 53.281358886 -4.4935012529 +14726 53.2835322662 -4.4987890193 +14727 53.2854037189 -4.504389339 +14728 53.2869572374 -4.5102543488 +14729 53.2881795327 -4.5163339036 +14730 53.2890601481 -4.5225760079 +14731 53.2895915492 -4.5289272644 +14732 53.2897691896 -4.5353333333 +14733 53.1983583333 -4.5412361111 +14734 53.2066468056 -4.5397092778 +14735 53.2069446068 -4.5446913844 +14736 53.2074573908 -4.5496247792 +14737 53.2081825 -4.5544837778 +14738 53.1993472222 -4.5561083333 +14739 53.1983583333 -4.5412361111 +14740 53.3026916667 -4.5370638889 +14741 53.2896954167 -4.5394639444 +14742 53.2897658191 -4.5344489699 +14743 53.2896188347 -4.5294386237 +14744 53.28925525 -4.5244591389 +14745 53.3017055556 -4.5221555556 +14746 53.3026916667 -4.5370638889 +14747 53.2794899167 -4.6082879167 +14748 53.2715534167 -4.5927136389 +14749 53.2739730646 -4.5897540887 +14750 53.2762584688 -4.5865109682 +14751 53.2783977222 -4.5830011389 +14752 53.2863302778 -4.5985659167 +14753 53.2794899167 -4.6082879167 +14754 53.2147212778 -4.4584117778 +14755 53.2247583056 -4.4780087222 +14756 53.2223411037 -4.4809704688 +14757 53.2200582086 -4.4842144577 +14758 53.2179214722 -4.4877238056 +14759 53.2078808611 -4.4681175556 +14760 53.2147212778 -4.4584117778 +14761 53.1351023087 -4.3376138889 +14762 53.1349257699 -4.3433043386 +14763 53.1343980293 -4.3489343296 +14764 53.1335246937 -4.3544440496 +14765 53.1323150412 -4.3597749729 +14766 53.1307819219 -4.364870486 +14767 53.1289416205 -4.3696764915 +14768 53.1268136824 -4.3741419857 +14769 53.1244207048 -4.3782196013 +14770 53.1217880954 -4.3818661114 +14771 53.1189438015 -4.3850428872 +14772 53.1159180117 -4.3877163068 +14773 53.1127428348 -4.3898581093 +14774 53.1094519572 -4.3914456909 +14775 53.1060802854 -4.3924623404 +14776 53.1026635745 -4.3928974115 +14777 53.0992380488 -4.3927464296 +14778 53.0958400175 -4.3920111343 +14779 53.09250549 -4.3906994541 +14780 53.0892697945 -4.3888254173 +14781 53.0861672042 -4.3864089981 +14782 53.0832305756 -4.3834758997 +14783 53.0804910008 -4.3800572789 +14784 53.0779774803 -4.3761894124 +14785 53.0757166167 -4.3719133111 +14786 53.0737323344 -4.3672742846 +14787 53.0720456282 -4.3623214621 +14788 53.070674342 -4.357107273 +14789 53.0696329815 -4.3516868947 +14790 53.0689325613 -4.3461176715 +14791 53.0685804894 -4.3404585112 +14792 53.0685804894 -4.3347692666 +14793 53.0689325613 -4.3291101063 +14794 53.0696329815 -4.3235408831 +14795 53.070674342 -4.3181205048 +14796 53.0720456282 -4.3129063157 +14797 53.0737323344 -4.3079534931 +14798 53.0757166167 -4.3033144667 +14799 53.0779774803 -4.2990383653 +14800 53.0804910008 -4.2951704989 +14801 53.0832305756 -4.2917518781 +14802 53.0861672042 -4.2888187797 +14803 53.0892697945 -4.2864023605 +14804 53.09250549 -4.2845283237 +14805 53.0958400175 -4.2832166435 +14806 53.0992380488 -4.2824813481 +14807 53.1026635745 -4.2823303663 +14808 53.1060802854 -4.2827654374 +14809 53.1094519572 -4.2837820869 +14810 53.1127428348 -4.2853696685 +14811 53.1159180117 -4.2875114709 +14812 53.1189438015 -4.2901848905 +14813 53.1217880954 -4.2933616663 +14814 53.1244207048 -4.2970081764 +14815 53.1268136824 -4.3010857921 +14816 53.1289416205 -4.3055512863 +14817 53.1307819219 -4.3103572918 +14818 53.1323150412 -4.3154528048 +14819 53.1335246937 -4.3207837282 +14820 53.1343980293 -4.3262934482 +14821 53.1349257699 -4.3319234391 +14822 53.1351023087 -4.3376138889 +14823 53.081825 -4.4103138889 +14824 53.0867385278 -4.3869033611 +14825 53.0894737148 -4.3889621559 +14826 53.0923094586 -4.3906033207 +14827 53.0952226944 -4.3918134167 +14828 53.0903111111 -4.4152138889 +14829 53.081825 -4.4103138889 +14830 53.1217694444 -4.2648611111 +14831 53.1168824722 -4.2882921389 +14832 53.114145571 -4.286237965 +14833 53.1113083851 -4.2846023923 +14834 53.1083940278 -4.2833986667 +14835 53.1132833333 -4.2599555556 +14836 53.1217694444 -4.2648611111 +14837 53.615002394 -3.0575277778 +14838 53.6148258671 -3.0632825546 +14839 53.6142981621 -3.0689761866 +14840 53.6134248857 -3.0745481834 +14841 53.6122153156 -3.0799393554 +14842 53.6106823016 -3.0850924473 +14843 53.608842128 -3.0899527491 +14844 53.6067143394 -3.0944686797 +14845 53.6043215321 -3.0985923365 +14846 53.6016891128 -3.1022800041 +14847 53.5988450274 -3.1054926184 +14848 53.5958194632 -3.108196179 +14849 53.5926445269 -3.1103621078 +14850 53.5893539031 -3.1119675482 +14851 53.5859824958 -3.1129956032 +14852 53.5825660578 -3.1134355093 +14853 53.5791408106 -3.1132827447 +14854 53.5757430602 -3.1125390718 +14855 53.572408813 -3.1112125119 +14856 53.5691733937 -3.1093172548 +14857 53.5660710724 -3.1068735025 +14858 53.5631347019 -3.1039072508 +14859 53.5603953712 -3.1004500096 +14860 53.5578820774 -3.0965384663 +14861 53.5556214197 -3.0922140949 +14862 53.55363732 -3.0875227163 +14863 53.5519507702 -3.0825140131 +14864 53.5505796121 -3.0772410052 +14865 53.5495383493 -3.0717594907 +14866 53.5488379951 -3.0661274586 +14867 53.5484859565 -3.0604044788 +14868 53.5484859565 -3.0546510767 +14869 53.5488379951 -3.048928097 +14870 53.5495383493 -3.0432960648 +14871 53.5505796121 -3.0378145503 +14872 53.5519507702 -3.0325415424 +14873 53.55363732 -3.0275328393 +14874 53.5556214197 -3.0228414607 +14875 53.5578820774 -3.0185170893 +14876 53.5603953712 -3.0146055459 +14877 53.5631347019 -3.0111483048 +14878 53.5660710724 -3.0081820531 +14879 53.5691733937 -3.0057383008 +14880 53.572408813 -3.0038430436 +14881 53.5757430602 -3.0025164838 +14882 53.5791408106 -3.0017728109 +14883 53.5825660578 -3.0016200463 +14884 53.5859824958 -3.0020599523 +14885 53.5893539031 -3.0030880073 +14886 53.5926445269 -3.0046934478 +14887 53.5958194632 -3.0068593766 +14888 53.5988450274 -3.0095629372 +14889 53.6016891128 -3.0127755514 +14890 53.6043215321 -3.0164632191 +14891 53.6067143394 -3.0205868758 +14892 53.608842128 -3.0251028064 +14893 53.6106823016 -3.0299631082 +14894 53.6122153156 -3.0351162002 +14895 53.6134248857 -3.0405073722 +14896 53.6142981621 -3.0460793689 +14897 53.6148258671 -3.051773001 +14898 53.615002394 -3.0575277778 +14899 53.5343348889 -3.0953566667 +14900 53.5509941389 -3.0789983056 +14901 53.5522709422 -3.0835627936 +14902 53.5537874214 -3.0879157218 +14903 53.55553125 -3.0920216944 +14904 53.5388743611 -3.1083726944 +14905 53.5343348889 -3.0953566667 +14906 53.6290938333 -3.0196293889 +14907 53.6124486667 -3.0360356111 +14908 53.6111705519 -3.031465676 +14909 53.609652509 -3.0271083965 +14910 53.6079069167 -3.0229993056 +14911 53.6245544167 -3.0065856389 +14912 53.6290938333 -3.0196293889 +14913 53.5660964167 -3.1378758889 +14914 53.5689110278 -3.1091354444 +14915 53.5717451964 -3.1108744368 +14916 53.5746614505 -3.1121752414 +14917 53.5776358333 -3.1130270833 +14918 53.5749635278 -3.1403126389 +14919 53.5660964167 -3.1378758889 +14920 53.5906015833 -2.9796778611 +14921 53.58837175 -3.002726 +14922 53.5853908477 -3.0019410534 +14923 53.5823798936 -3.0016131184 +14924 53.5793636389 -3.0017448056 +14925 53.5817345 -2.9772401944 +14926 53.5906015833 -2.9796778611 +14927 53.813265525 -3.0286111111 +14928 53.813087897 -3.0350967314 +14929 53.8125565327 -3.0415268553 +14930 53.8116759789 -3.0478464658 +14931 53.8104537697 -3.0540014992 +14932 53.8089003614 -3.0599393125 +14933 53.807029043 -3.0656091358 +14934 53.8048558208 -3.0709625102 +14935 53.8023992809 -3.0759537036 +14936 53.7996804291 -3.0805401032 +14937 53.7967225097 -3.0846825797 +14938 53.7935508061 -3.0883458215 +14939 53.7901924229 -3.0914986345 +14940 53.7866760536 -3.0941142068 +14941 53.783031734 -3.0961703336 +14942 53.7792905852 -3.0976496038 +14943 53.7754845467 -3.0985395433 +14944 53.7716461032 -3.0988327171 +14945 53.7678080074 -3.0985267866 +14946 53.764003 -3.0976245247 +14947 53.7602635307 -3.0961337862 +14948 53.7566214818 -3.0940674357 +14949 53.753107897 -3.0914432325 +14950 53.7497527174 -3.088283675 +14951 53.7465845272 -3.0846158053 +14952 53.7436303116 -3.0804709746 +14953 53.7409152277 -3.0758845751 +14954 53.7384623916 -3.0708957357 +14955 53.7362926829 -3.0655469893 +14956 53.734424568 -3.0598839103 +14957 53.7328739443 -3.0539547281 +14958 53.7316540056 -3.0478099183 +14959 53.7307751313 -3.0415017762 +14960 53.7302447983 -3.0350839746 +14961 53.7300675179 -3.0286111111 +14962 53.7302447983 -3.0221382476 +14963 53.7307751313 -3.015720446 +14964 53.7316540056 -3.0094123039 +14965 53.7328739443 -3.0032674941 +14966 53.734424568 -2.9973383119 +14967 53.7362926829 -2.9916752329 +14968 53.7384623916 -2.9863264865 +14969 53.7409152277 -2.9813376472 +14970 53.7436303116 -2.9767512476 +14971 53.7465845272 -2.972606417 +14972 53.7497527174 -2.9689385472 +14973 53.753107897 -2.9657789898 +14974 53.7566214818 -2.9631547866 +14975 53.7602635307 -2.961088436 +14976 53.764003 -2.9595976975 +14977 53.7678080074 -2.9586954356 +14978 53.7716461032 -2.9583895052 +14979 53.7754845467 -2.9586826789 +14980 53.7792905852 -2.9595726185 +14981 53.783031734 -2.9610518886 +14982 53.7866760536 -2.9631080155 +14983 53.7901924229 -2.9657235877 +14984 53.7935508061 -2.9688764007 +14985 53.7967225097 -2.9725396425 +14986 53.7996804291 -2.976682119 +14987 53.8023992809 -2.9812685186 +14988 53.8048558208 -2.986259712 +14989 53.807029043 -2.9916130864 +14990 53.8089003614 -2.9972829098 +14991 53.8104537697 -3.003220723 +14992 53.8116759789 -3.0093757564 +14993 53.8125565327 -3.0156953669 +14994 53.813087897 -3.0221254908 +14995 53.813265525 -3.0286111111 +14996 53.7713694444 -3.1188944444 +14997 53.7704148056 -3.0987998889 +14998 53.7734150578 -3.0987721547 +14999 53.7764063199 -3.0983793941 +15000 53.7793730278 -3.0976235833 +15001 53.780325 -3.1176611111 +15002 53.7713694444 -3.1188944444 +15003 53.7716805556 -2.93825 +15004 53.7726654167 -2.9584088889 +15005 53.769665424 -2.9584724548 +15006 53.7666759456 -2.9589008064 +15007 53.7637125278 -2.9596916389 +15008 53.762725 -2.9394777778 +15009 53.7716805556 -2.93825 +15010 53.7973527778 -3.106925 +15011 53.7903458056 -3.0913692778 +15012 53.7929841056 -3.0889268368 +15013 53.7955109174 -3.0861684105 +15014 53.797913 -3.0831083889 +15015 53.8044972222 -3.097725 +15016 53.7973527778 -3.106925 +15017 53.7454194444 -2.9668805556 +15018 53.74749825 -2.9714730833 +15019 53.7451145435 -2.9745715778 +15020 53.7428697567 -2.9779523219 +15021 53.7407756111 -2.9815976111 +15022 53.7382722222 -2.9760666667 +15023 53.7454194444 -2.9668805556 +15024 53.2196585709 -2.9777777778 +15025 53.2194809288 -2.9841733813 +15026 53.2189495226 -2.9905142623 +15027 53.218068899 -2.9967461703 +15028 53.2168465921 -3.0028157954 +15029 53.2152930587 -3.0086712274 +15030 53.2134215879 -3.0142624035 +15031 53.2112481864 -3.0195415387 +15032 53.2087914411 -3.0244635363 +15033 53.2060723582 -3.0289863748 +15034 53.2031141832 -3.0330714673 +15035 53.1999422005 -3.0366839906 +15036 53.1965835162 -3.0397931814 +15037 53.1930668254 -3.0423725966 +15038 53.1894221661 -3.0444003364 +15039 53.1856806614 -3.0458592271 +15040 53.1818742535 -3.0467369634 +15041 53.1780354301 -3.0470262088 +15042 53.1741969468 -3.0467246526 +15043 53.1703915479 -3.0458350247 +15044 53.1666516866 -3.0443650667 +15045 53.1630092492 -3.0423274606 +15046 53.1594952831 -3.0397397161 +15047 53.1561397334 -3.0366240167 +15048 53.1529711887 -3.0330070272 +15049 53.1500166378 -3.0289196629 +15050 53.1473012419 -3.0243968244 +15051 53.1448481206 -3.0194770986 +15052 53.1426781572 -3.0142024296 +15053 53.140809821 -3.0086177621 +15054 53.1392590123 -3.0027706593 +15055 53.1380389272 -2.9967109005 +15056 53.137159947 -2.9904900599 +15057 53.1366295498 -2.9841610705 +15058 53.1364522479 -2.9777777778 +15059 53.1366295498 -2.971394485 +15060 53.137159947 -2.9650654957 +15061 53.1380389272 -2.958844655 +15062 53.1392590123 -2.9527848963 +15063 53.140809821 -2.9469377935 +15064 53.1426781572 -2.9413531259 +15065 53.1448481206 -2.936078457 +15066 53.1473012419 -2.9311587312 +15067 53.1500166378 -2.9266358927 +15068 53.1529711887 -2.9225485284 +15069 53.1561397334 -2.9189315388 +15070 53.1594952831 -2.9158158395 +15071 53.1630092492 -2.913228095 +15072 53.1666516866 -2.9111904889 +15073 53.1703915479 -2.9097205308 +15074 53.1741969468 -2.9088309029 +15075 53.1780354301 -2.9085293468 +15076 53.1818742535 -2.9088185922 +15077 53.1856806614 -2.9096963285 +15078 53.1894221661 -2.9111552191 +15079 53.1930668254 -2.9131829589 +15080 53.1965835162 -2.9157623742 +15081 53.1999422005 -2.918871565 +15082 53.2031141832 -2.9224840883 +15083 53.2060723582 -2.9265691808 +15084 53.2087914411 -2.9310920193 +15085 53.2112481864 -2.9360140169 +15086 53.2134215879 -2.941293152 +15087 53.2152930587 -2.9468843281 +15088 53.2168465921 -2.9527397602 +15089 53.218068899 -2.9588093852 +15090 53.2189495226 -2.9650412933 +15091 53.2194809288 -2.9713821742 +15092 53.2196585709 -2.9777777778 +15093 53.136375 -3.028075 +15094 53.1438768889 -3.0172443611 +15095 53.1456745645 -3.021239603 +15096 53.1476405689 -3.0250093088 +15097 53.1497646944 -3.0285338889 +15098 53.1422694444 -3.0393527778 +15099 53.136375 -3.028075 +15100 53.2198527778 -2.9271138889 +15101 53.2122030556 -2.9382055556 +15102 53.2104006477 -2.9342095663 +15103 53.2084299101 -2.9304407113 +15104 53.2063011111 -2.9269186111 +15105 53.2139583333 -2.9158138889 +15106 53.2198527778 -2.9271138889 +15107 53.7866240444 -2.8834361111 +15108 53.7864464157 -2.889917622 +15109 53.7859150496 -2.8963436718 +15110 53.7850344927 -2.9026592785 +15111 53.783812279 -2.9088104129 +15112 53.7822588652 -2.9147444653 +15113 53.78038754 -2.9204106983 +15114 53.7782143098 -2.9257606835 +15115 53.7757577607 -2.9307487181 +15116 53.7730388986 -2.935332216 +15117 53.7700809678 -2.9394720729 +15118 53.7669092518 -2.9431329994 +15119 53.7635508551 -2.946283821 +15120 53.7600344714 -2.9488977427 +15121 53.7563901367 -2.9509525737 +15122 53.752648972 -2.9524309136 +15123 53.7488429169 -2.9533202961 +15124 53.7450044565 -2.9536132906 +15125 53.7411663433 -2.9533075598 +15126 53.7373613184 -2.9524058748 +15127 53.7336218315 -2.950916085 +15128 53.7299797653 -2.9488510467 +15129 53.7264661634 -2.9462285079 +15130 53.7231109672 -2.9430709527 +15131 53.7199427611 -2.9394054057 +15132 53.7169885305 -2.9352631985 +15133 53.7142734326 -2.9306797005 +15134 53.7118205837 -2.9256940162 +15135 53.7096508635 -2.9203486515 +15136 53.7077827387 -2.9146891521 +15137 53.7062321067 -2.9087637168 +15138 53.7050121615 -2.9026227897 +15139 53.7041332824 -2.896318633 +15140 53.7036029465 -2.8899048857 +15141 53.7034256651 -2.8834361111 +15142 53.7036029465 -2.8769673366 +15143 53.7041332824 -2.8705535893 +15144 53.7050121615 -2.8642494325 +15145 53.7062321067 -2.8581085054 +15146 53.7077827387 -2.8521830701 +15147 53.7096508635 -2.8465235707 +15148 53.7118205837 -2.841178206 +15149 53.7142734326 -2.8361925217 +15150 53.7169885305 -2.8316090238 +15151 53.7199427611 -2.8274668166 +15152 53.7231109672 -2.8238012695 +15153 53.7264661634 -2.8206437143 +15154 53.7299797653 -2.8180211755 +15155 53.7336218315 -2.8159561372 +15156 53.7373613184 -2.8144663475 +15157 53.7411663433 -2.8135646624 +15158 53.7450044565 -2.8132589317 +15159 53.7488429169 -2.8135519261 +15160 53.752648972 -2.8144413086 +15161 53.7563901367 -2.8159196485 +15162 53.7600344714 -2.8179744795 +15163 53.7635508551 -2.8205884012 +15164 53.7669092518 -2.8237392229 +15165 53.7700809678 -2.8274001493 +15166 53.7730388986 -2.8315400062 +15167 53.7757577607 -2.8361235041 +15168 53.7782143098 -2.8411115387 +15169 53.78038754 -2.846461524 +15170 53.7822588652 -2.8521277569 +15171 53.783812279 -2.8580618093 +15172 53.7850344927 -2.8642129437 +15173 53.7859150496 -2.8705285504 +15174 53.7864464157 -2.8769546003 +15175 53.7866240444 -2.8834361111 +15176 53.7228194444 -2.9695861111 +15177 53.72740525 -2.9469941389 +15178 53.730166133 -2.9489722681 +15179 53.7330043435 -2.9506099817 +15180 53.7359051389 -2.9518986944 +15181 53.7313222222 -2.974475 +15182 53.7228194444 -2.9695861111 +15183 53.7671638889 -2.7972166667 +15184 53.7626105556 -2.8198246111 +15185 53.7598472272 -2.8178532713 +15186 53.7570068727 -2.8162233905 +15187 53.7541042778 -2.8149433889 +15188 53.7586611111 -2.7923166667 +15189 53.7671638889 -2.7972166667 +15190 53.3752130345 -2.8497222222 +15191 53.3750353962 -2.8561411049 +15192 53.3745040011 -2.862505065 +15193 53.3736233958 -2.8687596537 +15194 53.3724011146 -2.8748513663 +15195 53.3708476142 -2.8807281029 +15196 53.3689761835 -2.8863396181 +15197 53.3668028293 -2.8916379523 +15198 53.364346138 -2.8965778448 +15199 53.361627116 -2.901117121 +15200 53.3586690083 -2.9052170537 +15201 53.355497099 -2.9088426935 +15202 53.3521384939 -2.9119631657 +15203 53.3486218877 -2.9145519318 +15204 53.3449773177 -2.916587013 +15205 53.3412359065 -2.9180511743 +15206 53.3374295957 -2.9189320668 +15207 53.333590872 -2.9192223284 +15208 53.3297524905 -2.9189196412 +15209 53.3259471944 -2.9180267463 +15210 53.322207436 -2.9165514144 +15211 53.3185651006 -2.9145063748 +15212 53.3150512345 -2.9119092018 +15213 53.311695782 -2.9087821604 +15214 53.3085273302 -2.9051520127 +15215 53.3055728673 -2.9010497869 +15216 53.3028575532 -2.8965105107 +15217 53.3004045067 -2.8915729112 +15218 53.29823461 -2.8862790848 +15219 53.2963663318 -2.880674139 +15220 53.2948155716 -2.8748058092 +15221 53.2935955249 -2.868724055 +15222 53.2927165725 -2.8624806369 +15223 53.2921861921 -2.8561286793 +15224 53.2920088958 -2.8497222222 +15225 53.2921861921 -2.8433157651 +15226 53.2927165725 -2.8369638075 +15227 53.2935955249 -2.8307203894 +15228 53.2948155716 -2.8246386352 +15229 53.2963663318 -2.8187703055 +15230 53.29823461 -2.8131653596 +15231 53.3004045067 -2.8078715332 +15232 53.3028575532 -2.8029339337 +15233 53.3055728673 -2.7983946575 +15234 53.3085273302 -2.7942924318 +15235 53.311695782 -2.7906622841 +15236 53.3150512345 -2.7875352426 +15237 53.3185651006 -2.7849380696 +15238 53.322207436 -2.78289303 +15239 53.3259471944 -2.7814176981 +15240 53.3297524905 -2.7805248032 +15241 53.333590872 -2.7802221161 +15242 53.3374295957 -2.7805123776 +15243 53.3412359065 -2.7813932701 +15244 53.3449773177 -2.7828574314 +15245 53.3486218877 -2.7848925127 +15246 53.3521384939 -2.7874812787 +15247 53.355497099 -2.7906017509 +15248 53.3586690083 -2.7942273907 +15249 53.361627116 -2.7983273235 +15250 53.364346138 -2.8028665997 +15251 53.3668028293 -2.8078064921 +15252 53.3689761835 -2.8131048264 +15253 53.3708476142 -2.8187163415 +15254 53.3724011146 -2.8245930782 +15255 53.3736233958 -2.8306847907 +15256 53.3745040011 -2.8369393794 +15257 53.3750353962 -2.8433033395 +15258 53.3752130345 -2.8497222222 +15259 53.3249333333 -2.9402555556 +15260 53.3259700278 -2.9180339167 +15261 53.3289367765 -2.9187785016 +15262 53.3319279325 -2.9191640932 +15263 53.3349279444 -2.9191886111 +15264 53.3338916667 -2.9414 +15265 53.3249333333 -2.9402555556 +15266 53.3423027778 -2.7584444444 +15267 53.3412629167 -2.7814016667 +15268 53.3382957709 -2.7806603436 +15269 53.3353043619 -2.7802782982 +15270 53.33230425 -2.7802574444 +15271 53.3333444444 -2.7572916667 +15272 53.3423027778 -2.7584444444 +15273 53.3953507267 -2.2749509722 +15274 53.3951730888 -2.2813728845 +15275 53.3946416951 -2.2877398481 +15276 53.3937610922 -2.2939973885 +15277 53.3925388144 -2.3000919755 +15278 53.3909853182 -2.3059714848 +15279 53.3891138927 -2.3115856468 +15280 53.3869405445 -2.3168864796 +15281 53.3844838603 -2.3218287009 +15282 53.3817648461 -2.3263701163 +15283 53.3788067471 -2.3304719804 +15284 53.3756348473 -2.3340993272 +15285 53.3722762524 -2.3372212675 +15286 53.3687596571 -2.3398112505 +15287 53.3651150987 -2.3418472871 +15288 53.3613736996 -2.3433121343 +15289 53.3575674013 -2.3441934376 +15290 53.3537286906 -2.3444838314 +15291 53.3498903223 -2.344180997 +15292 53.3460850394 -2.3432876769 +15293 53.3423452944 -2.3418116456 +15294 53.3387029721 -2.3397656387 +15295 53.335189119 -2.3371672386 +15296 53.331833679 -2.3340387211 +15297 53.3286652393 -2.330406861 +15298 53.3257107877 -2.3263027012 +15299 53.3229954842 -2.3217612858 +15300 53.3205424474 -2.3168213602 +15301 53.3183725594 -2.3115250407 +15302 53.3165042887 -2.3059174558 +15303 53.3149535347 -2.3000463636 +15304 53.3137334931 -2.2939617469 +15305 53.3128545442 -2.2877153906 +15306 53.312324166 -2.2813604439 +15307 53.3121468705 -2.2749509722 +15308 53.312324166 -2.2685415005 +15309 53.3128545442 -2.2621865539 +15310 53.3137334931 -2.2559401975 +15311 53.3149535347 -2.2498555809 +15312 53.3165042887 -2.2439844887 +15313 53.3183725594 -2.2383769038 +15314 53.3205424474 -2.2330805842 +15315 53.3229954842 -2.2281406587 +15316 53.3257107877 -2.2235992433 +15317 53.3286652393 -2.2194950835 +15318 53.331833679 -2.2158632233 +15319 53.335189119 -2.2127347058 +15320 53.3387029721 -2.2101363058 +15321 53.3423452944 -2.2080902988 +15322 53.3460850394 -2.2066142676 +15323 53.3498903223 -2.2057209474 +15324 53.3537286906 -2.2054181131 +15325 53.3575674013 -2.2057085069 +15326 53.3613736996 -2.2065898101 +15327 53.3651150987 -2.2080546573 +15328 53.3687596571 -2.210090694 +15329 53.3722762524 -2.2126806769 +15330 53.3756348473 -2.2158026173 +15331 53.3788067471 -2.2194299641 +15332 53.3817648461 -2.2235318281 +15333 53.3844838603 -2.2280732435 +15334 53.3869405445 -2.2330154648 +15335 53.3891138927 -2.2383162976 +15336 53.3909853182 -2.2439304597 +15337 53.3925388144 -2.2498099689 +15338 53.3937610922 -2.255904556 +15339 53.3946416951 -2.2621620964 +15340 53.3951730888 -2.2685290599 +15341 53.3953507267 -2.2749509722 +15342 53.3158111111 -2.3414111111 +15343 53.324307 -2.3238734167 +15344 53.3264781521 -2.3273308396 +15345 53.3288109833 -2.3304832641 +15346 53.3312738611 -2.3333465833 +15347 53.3228 -2.3508361111 +15348 53.3158111111 -2.3414111111 +15349 53.3930222222 -2.2055305556 +15350 53.3832712778 -2.2257580556 +15351 53.3810587658 -2.2223686207 +15352 53.3787240926 -2.2192198687 +15353 53.3762599167 -2.2163605833 +15354 53.3860333333 -2.1960833333 +15355 53.3930222222 -2.2055305556 +15356 53.3002166667 -2.3642722222 +15357 53.3219233611 -2.3194853889 +15358 53.3239194034 -2.3232527059 +15359 53.3260924911 -2.326738245 +15360 53.3284110278 -2.3299518889 +15361 53.3072055556 -2.3736972222 +15362 53.3002166667 -2.3642722222 +15363 53.4382972222 -2.3907305556 +15364 53.4438888889 -2.3827777778 +15365 53.4635694444 -2.3355777778 +15366 53.4669212271 -2.3343558953 +15367 53.4703398171 -2.3338295699 +15368 53.473772581 -2.3338945616 +15369 53.4771831975 -2.3345503253 +15370 53.4805355709 -2.3357900617 +15371 53.4837942136 -2.3376007831 +15372 53.4869246223 -2.3399634458 +15373 53.4898936441 -2.3428531463 +15374 53.4926698285 -2.3462393808 +15375 53.4952237618 -2.3500863655 +15376 53.49752838 -2.3543534126 +15377 53.4995592571 -2.3589953605 +15378 53.5012948649 -2.3639630523 +15379 53.502716803 -2.3692038574 +15380 53.5038099946 -2.3746622316 +15381 53.5045628477 -2.3802803087 +15382 53.5049673785 -2.3859985173 +15383 53.5050192971 -2.391756217 +15384 53.5047180527 -2.3974923454 +15385 53.5040668403 -2.4031460708 +15386 53.5030725655 -2.4086574411 +15387 53.5017457719 -2.4139680243 +15388 53.5001005278 -2.4190215316 +15389 53.4981542763 -2.4237644171 +15390 53.4959276492 -2.4281464477 +15391 53.4934442471 -2.4321212367 +15392 53.490730388 -2.4356467354 +15393 53.4878148267 -2.4386856781 +15394 53.4847284494 -2.4412059746 +15395 53.4815039446 -2.4431810468 +15396 53.4781754567 -2.4445901066 +15397 53.4747782227 -2.4454183711 +15398 53.4713481991 -2.4456572136 +15399 53.4679216808 -2.4453042492 +15400 53.464534917 -2.4443633537 +15401 53.4612237276 -2.4428446174 +15402 53.4580231253 -2.4407642317 +15403 53.4549669457 -2.4381443133 +15404 53.4520874903 -2.4350126656 +15405 53.4494151868 -2.4314024809 +15406 53.4469782683 -2.4273519867 +15407 53.4448024765 -2.4229040406 +15408 53.442910791 -2.4181056758 +15409 53.4413231879 -2.4130076057 +15410 53.4400564305 -2.407663689 +15411 53.4391238927 -2.4021303634 +15412 53.4385354193 -2.3964660531 +15413 53.4382972222 -2.3907305556 +15414 53.4254111111 -2.401275 +15415 53.4384753889 -2.395574 +15416 53.4389250988 -2.4005470392 +15417 53.43964046 -2.4054320863 +15418 53.4406156667 -2.4101894444 +15419 53.4276777778 -2.4158305556 +15420 53.4254111111 -2.401275 +15421 53.5186583333 -2.3760861111 +15422 53.5045544444 -2.3822588889 +15423 53.5040188623 -2.3773016223 +15424 53.5032188044 -2.3724457077 +15425 53.5021608056 -2.3677307778 +15426 53.5163916667 -2.3614972222 +15427 53.5186583333 -2.3760861111 +15428 53.4613111111 -2.469125 +15429 53.4632409444 -2.4437155833 +15430 53.466179194 -2.4447561923 +15431 53.469161453 -2.4453488031 +15432 53.4721634444 -2.4454885 +15433 53.470225 -2.4710111111 +15434 53.4613111111 -2.469125 +15435 53.4822083333 -2.312025 +15436 53.4804198611 -2.3359380833 +15437 53.4774914143 -2.3348219146 +15438 53.4745148593 -2.334152951 +15439 53.4715144444 -2.3339365278 +15440 53.4732944444 -2.3101361111 +15441 53.4822083333 -2.312025 +15442 53.4611444444 -2.4681555556 +15443 53.4629968056 -2.4436079722 +15444 53.4659298221 -2.4446857783 +15445 53.4689088672 -2.4453162818 +15446 53.4719096944 -2.4454942778 +15447 53.4700583333 -2.4700277778 +15448 53.4611444444 -2.4681555556 +15449 53.4819472222 -2.3112611111 +15450 53.4801236111 -2.3358037778 +15451 53.4771895373 -2.3347330633 +15452 53.4742098286 -2.3341101379 +15453 53.47120875 -2.3339399722 +15454 53.4730333333 -2.3093833333 +15455 53.4819472222 -2.3112611111 +15456 53.5017388889 -2.4483 +15457 53.4927476389 -2.4327602222 +15458 53.4949799004 -2.4293792212 +15459 53.4970209071 -2.4256737115 +15460 53.4988539444 -2.4216739444 +15461 53.5081833333 -2.4377944444 +15462 53.5017388889 -2.4483 +15463 53.4430694444 -2.3255083333 +15464 53.4574508611 -2.3502631944 +15465 53.4522123889 -2.3628273056 +15466 53.4366277778 -2.3359944444 +15467 53.4430694444 -2.3255083333 +15468 53.9076232001 -1.6607694444 +15469 53.9074455742 -1.6672696727 +15470 53.9069142166 -1.6737142792 +15471 53.9060336738 -1.680048122 +15472 53.9048114799 -1.6862170157 +15473 53.9032580914 -1.6921681977 +15474 53.9013867969 -1.6978507839 +15475 53.899213603 -1.7032162058 +15476 53.8967570955 -1.7082186283 +15477 53.8940382802 -1.7128153425 +15478 53.8910804012 -1.7169671311 +15479 53.8879087416 -1.7206386033 +15480 53.884550406 -1.7237984952 +15481 53.8810340875 -1.7264199347 +15482 53.8773898217 -1.728480668 +15483 53.8736487292 -1.7299632451 +15484 53.8698427491 -1.7308551647 +15485 53.8660043658 -1.7311489757 +15486 53.8621663314 -1.7308423351 +15487 53.858361386 -1.7299380227 +15488 53.8546219788 -1.7284439118 +15489 53.8509799916 -1.7263728964 +15490 53.8474664672 -1.7237427766 +15491 53.8441113463 -1.7205761018 +15492 53.8409432124 -1.7168999752 +15493 53.83798905 -1.712745819 +15494 53.8352740157 -1.7081491048 +15495 53.8328212248 -1.7031490498 +15496 53.8306515566 -1.6977882823 +15497 53.8287834768 -1.692112479 +15498 53.8272328825 -1.6861699773 +15499 53.8260129671 -1.6800113658 +15500 53.8251341097 -1.6736890567 +15501 53.8246037868 -1.6672568431 +15502 53.8244265098 -1.6607694444 +15503 53.8246037868 -1.6542820458 +15504 53.8251341097 -1.6478498321 +15505 53.8260129671 -1.6415275231 +15506 53.8272328825 -1.6353689116 +15507 53.8287834768 -1.6294264099 +15508 53.8306515566 -1.6237506065 +15509 53.8328212248 -1.6183898391 +15510 53.8352740157 -1.6133897841 +15511 53.83798905 -1.6087930699 +15512 53.8409432124 -1.6046389137 +15513 53.8441113463 -1.6009627871 +15514 53.8474664672 -1.5977961123 +15515 53.8509799916 -1.5951659925 +15516 53.8546219788 -1.5930949771 +15517 53.858361386 -1.5916008662 +15518 53.8621663314 -1.5906965538 +15519 53.8660043658 -1.5903899132 +15520 53.8698427491 -1.5906837242 +15521 53.8736487292 -1.5915756438 +15522 53.8773898217 -1.5930582209 +15523 53.8810340875 -1.5951189542 +15524 53.884550406 -1.5977403937 +15525 53.8879087416 -1.6009002856 +15526 53.8910804012 -1.6045717577 +15527 53.8940382802 -1.6087235464 +15528 53.8967570955 -1.6133202606 +15529 53.899213603 -1.618322683 +15530 53.9013867969 -1.623688105 +15531 53.9032580914 -1.6293706912 +15532 53.9048114799 -1.6353218732 +15533 53.9060336738 -1.6414907669 +15534 53.9069142166 -1.6478246097 +15535 53.9074455742 -1.6542692162 +15536 53.9076232001 -1.6607694444 +15537 53.9016444444 -1.7258722222 +15538 53.8936015278 -1.7134789444 +15539 53.8957754389 -1.7099776463 +15540 53.8977945137 -1.7062197951 +15541 53.8996482222 -1.7022249444 +15542 53.9076861111 -1.7146083333 +15543 53.9016444444 -1.7258722222 +15544 53.8301222222 -1.5953916667 +15545 53.8384270556 -1.6081265 +15546 53.8362559837 -1.6116280666 +15547 53.834239724 -1.6153847414 +15548 53.83238875 -1.619377 +15549 53.8240777778 -1.6066305556 +15550 53.8301222222 -1.5953916667 +15551 53.8102666667 -1.2527638889 +15552 53.8079780693 -1.2571224026 +15553 53.8054348301 -1.2610571872 +15554 53.8026642646 -1.2645260612 +15555 53.7996961247 -1.2674918691 +15556 53.7965622774 -1.2699228782 +15557 53.7932963613 -1.2717931161 +15558 53.789933425 -1.2730826444 +15559 53.7865095498 -1.2737777682 +15560 53.7830614618 -1.2738711768 +15561 53.779626138 -1.2733620161 +15562 53.7762404097 -1.2722558913 +15563 53.7729405674 -1.2705648008 +15564 53.7697619731 -1.2683070016 +15565 53.7667386813 -1.2655068083 +15566 53.7639030758 -1.2621943278 +15567 53.7612855237 -1.2584051335 +15568 53.7589140514 -1.2541798811 +15569 53.7568140463 -1.2495638721 +15570 53.7550079858 -1.2446065683 +15571 53.7535151986 -1.2393610627 +15572 53.7523516589 -1.2338835135 +15573 53.7515298163 -1.2282325455 +15574 53.7510584638 -1.2224686263 +15575 53.7509426443 -1.2166534236 +15576 53.7511835969 -1.2108491499 +15577 53.7517787436 -1.2051179016 +15578 53.7527217173 -1.1995209993 +15579 53.7540024286 -1.1941183362 +15580 53.7556071738 -1.1889677411 +15581 53.75751878 -1.1841243629 +15582 53.759716788 -1.1796400828 +15583 53.7621776702 -1.1755629604 +15584 53.7648750804 -1.1719367193 +15585 53.7677801353 -1.1688002784 +15586 53.7708617218 -1.1661873332 +15587 53.7740868293 -1.1641259915 +15588 53.7774209021 -1.1626384686 +15589 53.7808282085 -1.1617408441 +15590 53.7842722237 -1.1614428842 +15591 53.78771602 -1.1617479309 +15592 53.7911226633 -1.1626528599 +15593 53.7944556092 -1.1641481077 +15594 53.7976790953 -1.1662177682 +15595 53.8007585255 -1.168839758 +15596 53.8036608427 -1.1719860481 +15597 53.8063611111 -1.1756111111 +15598 53.8102666667 -1.2527638889 +15599 53.7393833333 -1.21695 +15600 53.7510245278 -1.2141693611 +15601 53.7509727092 -1.219247129 +15602 53.7511927928 -1.2243120647 +15603 53.751683 -1.2293228333 +15604 53.7406444444 -1.2319555556 +15605 53.7393833333 -1.21695 +15606 53.8342722222 -1.2095805556 +15607 53.8084004444 -1.2157734444 +15608 53.8076328889 -1.2006255278 +15609 53.8330111111 -1.1945416667 +15610 53.8342722222 -1.2095805556 +15611 53.7592861111 -1.2829833333 +15612 53.76597425 -1.2646393333 +15613 53.7685715594 -1.267242897 +15614 53.771297993 -1.2694385055 +15615 53.7741311111 -1.271208 +15616 53.7669444444 -1.2909194444 +15617 53.7592861111 -1.2829833333 +15618 53.8170138889 -1.1532638889 +15619 53.8066739167 -1.1817541111 +15620 53.8063611111 -1.1756111111 +15621 53.8036694701 -1.1720433532 +15622 53.8007938611 -1.1689177222 +15623 53.8093583333 -1.1453166667 +15624 53.8170138889 -1.1532638889 +15625 53.7910472222 -1.2993888889 +15626 53.7874488056 -1.2736092222 +15627 53.7904214951 -1.2728948949 +15628 53.7933439481 -1.2717308379 +15629 53.7961923611 -1.2701264444 +15630 53.7997888889 -1.2958916667 +15631 53.7910472222 -1.2993888889 +15632 53.7778166667 -1.1391666667 +15633 53.7809968611 -1.1617503611 +15634 53.7780250319 -1.1624732323 +15635 53.7751038792 -1.1636452747 +15636 53.7722571667 -1.1652568333 +15637 53.769075 -1.1426583333 +15638 53.7778166667 -1.1391666667 +15639 53.7915666667 -1.2986611111 +15640 53.7880835278 -1.2734953889 +15641 53.7910487701 -1.2726844522 +15642 53.7939586218 -1.2714251173 +15643 53.7967893611 -1.2697275556 +15644 53.8003138889 -1.2951916667 +15645 53.7915666667 -1.2986611111 +15646 53.7785027778 -1.1383 +15647 53.7817617222 -1.1616384444 +15648 53.7787795064 -1.1622457931 +15649 53.7758418658 -1.1633045603 +15650 53.7729727222 -1.1648060278 +15651 53.7697555556 -1.1417666667 +15652 53.7785027778 -1.1383 +15653 53.350214989 -1.1962027778 +15654 53.3500384556 -1.2019218329 +15655 53.349510731 -1.2075801243 +15656 53.348637422 -1.2131175379 +15657 53.3474278065 -1.2184752531 +15658 53.3458947345 -1.2235963708 +15659 53.3440544906 -1.2284265212 +15660 53.3419266197 -1.2329144439 +15661 53.3395337186 -1.2370125336 +15662 53.3369011946 -1.240677346 +15663 53.3340569944 -1.2438700589 +15664 53.3310313059 -1.246556882 +15665 53.327856237 -1.2487094133 +15666 53.3245654734 -1.2503049366 +15667 53.3211939204 -1.2513266582 +15668 53.317777332 -1.2517638795 +15669 53.3143519312 -1.251612105 +15670 53.3109540261 -1.2508730844 +15671 53.3076196243 -1.2495547875 +15672 53.3043840527 -1.2476713144 +15673 53.3012815831 -1.2452427405 +15674 53.2983450703 -1.2422948993 +15675 53.2956056051 -1.2388591045 +15676 53.2930921862 -1.2349718154 +15677 53.2908314149 -1.2306742488 +15678 53.2888472145 -1.2260119419 +15679 53.2871605784 -1.2210342697 +15680 53.2857893497 -1.2157939244 +15681 53.2847480331 -1.2103463594 +15682 53.2840476424 -1.2047492055 +15683 53.2836955854 -1.1990616652 +15684 53.2836955854 -1.1933438903 +15685 53.2840476424 -1.18765635 +15686 53.2847480331 -1.1820591962 +15687 53.2857893497 -1.1766116311 +15688 53.2871605784 -1.1713712859 +15689 53.2888472145 -1.1663936137 +15690 53.2908314149 -1.1617313067 +15691 53.2930921862 -1.1574337402 +15692 53.2956056051 -1.1535464511 +15693 53.2983450703 -1.1501106563 +15694 53.3012815831 -1.147162815 +15695 53.3043840527 -1.1447342412 +15696 53.3076196243 -1.142850768 +15697 53.3109540261 -1.1415324711 +15698 53.3143519312 -1.1407934505 +15699 53.317777332 -1.1406416761 +15700 53.3211939204 -1.1410788974 +15701 53.3245654734 -1.1421006189 +15702 53.327856237 -1.1436961423 +15703 53.3310313059 -1.1458486736 +15704 53.3340569944 -1.1485354967 +15705 53.3369011946 -1.1517282095 +15706 53.3395337186 -1.155393022 +15707 53.3419266197 -1.1594911116 +15708 53.3440544906 -1.1639790343 +15709 53.3458947345 -1.1688091847 +15710 53.3474278065 -1.1739303024 +15711 53.348637422 -1.1792880176 +15712 53.349510731 -1.1848254313 +15713 53.3500384556 -1.1904837226 +15714 53.350214989 -1.1962027778 +15715 53.2867333333 -1.2560277778 +15716 53.294504 -1.2372535278 +15717 53.2968114135 -1.2404625371 +15718 53.2992826763 -1.2433116277 +15719 53.3018976944 -1.2457775556 +15720 53.2941305556 -1.2645416667 +15721 53.2867333333 -1.2560277778 +15722 53.3468555556 -1.1368916667 +15723 53.33934775 -1.1551079444 +15724 53.3370379636 -1.1519003867 +15725 53.3345644339 -1.1490541355 +15726 53.3319473333 -1.1465923333 +15727 53.3394583333 -1.1283666667 +15728 53.3468555556 -1.1368916667 +15729 53.3626888889 -1.2100472222 +15730 53.3494531667 -1.2080307222 +15731 53.3499592268 -1.2030826375 +15732 53.350196059 -1.1980783779 +15733 53.35016175 -1.1930588056 +15734 53.3635027778 -1.1950861111 +15735 53.3626888889 -1.2100472222 +15736 53.2714222222 -1.1811194444 +15737 53.2845884722 -1.1831127778 +15738 53.2840134665 -1.1880312955 +15739 53.28370629 -1.1930161911 +15740 53.2836694444 -1.1980269722 +15741 53.2706083333 -1.1960444444 +15742 53.2714222222 -1.1811194444 +15743 53.8102666667 -1.2527638889 +15744 53.8063611111 -1.1756111111 +15745 53.8041867195 -1.1725646884 +15746 53.8018525338 -1.1698741737 +15747 53.7993918007 -1.16752756 +15748 53.7968222222 -1.1655416667 +15749 53.7985792559 -1.1597722034 +15750 53.8006786956 -1.1543354207 +15751 53.8030656328 -1.1492480814 +15752 53.8057197929 -1.1445534596 +15753 53.8086186276 -1.1402915157 +15754 53.8117375048 -1.1364985567 +15755 53.8150499175 -1.1332069262 +15756 53.8185277071 -1.130444727 +15757 53.8221413022 -1.12823558 +15758 53.8258599689 -1.1265984186 +15759 53.8296520715 -1.1255473238 +15760 53.833485341 -1.1250913997 +15761 53.8373271494 -1.1252346899 +15762 53.8411447868 -1.1259761385 +15763 53.8449057406 -1.1273095927 +15764 53.8485779722 -1.1292238505 +15765 53.8521301907 -1.1317027504 +15766 53.8555321199 -1.1347253046 +15767 53.8587547576 -1.1382658734 +15768 53.8617706235 -1.142294381 +15769 53.8645539948 -1.1467765685 +15770 53.8670811269 -1.1516742846 +15771 53.869330457 -1.15694581 +15772 53.8712827894 -1.1625462135 +15773 53.8729214607 -1.1684277362 +15774 53.8742324824 -1.1745402006 +15775 53.8752046623 -1.1808314416 +15776 53.8758296999 -1.1872477547 +15777 53.8761022585 -1.1937343584 +15778 53.8760200107 -1.2002358655 +15779 53.8755836588 -1.2066967607 +15780 53.8747969287 -1.2130618783 +15781 53.8736665375 -1.2192768777 +15782 53.8722021362 -1.2252887108 +15783 53.870416226 -1.231046079 +15784 53.8683240512 -1.2364998728 +15785 53.8659434677 -1.2416035943 +15786 53.8632947898 -1.2463137542 +15787 53.8604006154 -1.2505902441 +15788 53.8572856321 -1.254396678 +15789 53.8539764054 -1.2577007011 +15790 53.8505011509 -1.260474264 +15791 53.8468894926 -1.262693858 +15792 53.8431722097 -1.2643407125 +15793 53.8393809731 -1.2654009498 +15794 53.8355480755 -1.2658656989 +15795 53.8317061553 -1.2657311656 +15796 53.8278879192 -1.2649986589 +15797 53.8241258631 -1.2636745748 +15798 53.8204519965 -1.2617703363 +15799 53.8168975701 -1.2593022908 +15800 53.8134928111 -1.2562915665 +15801 53.8102666667 -1.2527638889 +15802 53.8007361111 -1.2626944444 +15803 53.8096936667 -1.2413818333 +15804 53.8102666667 -1.2527638889 +15805 53.8122140415 -1.2548809198 +15806 53.8142020278 -1.25688125 +15807 53.8080694444 -1.2714694444 +15808 53.8007361111 -1.2626944444 +15809 53.8689194444 -1.1263416667 +15810 53.8620370833 -1.1427984167 +15811 53.859719205 -1.1395753351 +15812 53.857269953 -1.1366436064 +15813 53.8547020833 -1.1340184722 +15814 53.8615888889 -1.11755 +15815 53.8689194444 -1.1263416667 +15816 53.5168842639 -1.0041361111 +15817 53.5167066289 -1.0105763852 +15818 53.5161752438 -1.0169615527 +15819 53.5152946553 -1.0232369828 +15820 53.5140723974 -1.0293489916 +15821 53.5125189269 -1.0352453051 +15822 53.5106475327 -1.0408755098 +15823 53.5084742213 -1.0461914861 +15824 53.5060175791 -1.0511478222 +15825 53.5032986123 -1.0557022029 +15826 53.5003405657 -1.0598157723 +15827 53.4971687231 -1.0634534648 +15828 53.49381019 -1.0665843034 +15829 53.4902936605 -1.0691816618 +15830 53.4866491717 -1.0712234889 +15831 53.4829078456 -1.0726924933 +15832 53.479101623 -1.0735762858 +15833 53.4752629901 -1.073867481 +15834 53.4714247011 -1.0735637544 +15835 53.4676194985 -1.0726678572 +15836 53.4638798337 -1.0711875872 +15837 53.460237591 -1.0691357169 +15838 53.456723816 -1.0665298799 +15839 53.4533684518 -1.0633924162 +15840 53.4502000847 -1.0597501774 +15841 53.4472457018 -1.0556342954 +15842 53.4445304622 -1.0510799147 +15843 53.4420774838 -1.0461258912 +15844 53.4399076479 -1.0408144611 +15845 53.4380394225 -1.0351908816 +15846 53.4364887065 -1.0293030466 +15847 53.4352686948 -1.023201081 +15848 53.4343897676 -1.0169369166 +15849 53.4338594025 -1.0105638537 +15850 53.4336821114 -1.0041361111 +15851 53.4338594025 -0.9977083685 +15852 53.4343897676 -0.9913353056 +15853 53.4352686948 -0.9850711413 +15854 53.4364887065 -0.9789691756 +15855 53.4380394225 -0.9730813406 +15856 53.4399076479 -0.9674577611 +15857 53.4420774838 -0.9621463311 +15858 53.4445304622 -0.9571923075 +15859 53.4472457018 -0.9526379268 +15860 53.4502000847 -0.9485220448 +15861 53.4533684518 -0.9448798061 +15862 53.456723816 -0.9417423423 +15863 53.460237591 -0.9391365054 +15864 53.4638798337 -0.9370846351 +15865 53.4676194985 -0.935604365 +15866 53.4714247011 -0.9347084678 +15867 53.4752629901 -0.9344047413 +15868 53.479101623 -0.9346959364 +15869 53.4829078456 -0.935579729 +15870 53.4866491717 -0.9370487333 +15871 53.4902936605 -0.9390905604 +15872 53.49381019 -0.9416879189 +15873 53.4971687231 -0.9448187574 +15874 53.5003405657 -0.9484564499 +15875 53.5032986123 -0.9525700193 +15876 53.5060175791 -0.9571244001 +15877 53.5084742213 -0.9620807361 +15878 53.5106475327 -0.9673967124 +15879 53.5125189269 -0.9730269171 +15880 53.5140723974 -0.9789232306 +15881 53.5152946553 -0.9850352394 +15882 53.5161752438 -0.9913106695 +15883 53.5167066289 -0.997695837 +15884 53.5168842639 -1.0041361111 +15885 53.4200222222 -1.0256888889 +15886 53.43451025 -1.0179736389 +15887 53.4352110427 -1.0228580729 +15888 53.4361200141 -1.0276454322 +15889 53.4372324444 -1.0323108889 +15890 53.4227472222 -1.0400194444 +15891 53.4200222222 -1.0256888889 +15892 53.5305361111 -0.982525 +15893 53.516054 -0.9902676111 +15894 53.5153516002 -0.9853739193 +15895 53.5144406157 -0.9805780853 +15896 53.5133258056 -0.9759051111 +15897 53.5278111111 -0.9681555556 +15898 53.5305361111 -0.982525 +15899 53.3138374154 -0.9513888889 +15900 53.3136608811 -0.9571030807 +15901 53.3131331538 -0.9627565605 +15902 53.3122598403 -0.9682892658 +15903 53.3110502186 -0.973642426 +15904 53.3095171386 -0.9787591905 +15905 53.307676885 -0.983585236 +15906 53.3055490027 -0.9880693455 +15907 53.3031560887 -0.9921639543 +15908 53.3005235503 -0.995825655 +15909 53.2976793342 -0.9990156584 +15910 53.2946536287 -1.0017002027 +15911 53.2914785415 -1.0038509099 +15912 53.2881877587 -1.0054450831 +15913 53.2848161856 -1.0064659423 +15914 53.2813995765 -1.0069027981 +15915 53.2779741546 -1.0067511584 +15916 53.2745762281 -1.0060127711 +15917 53.2712418052 -1.0046955992 +15918 53.2680062126 -1.0028137304 +15919 53.2649037226 -1.000387223 +15920 53.2619671902 -0.9974418883 +15921 53.2592277065 -0.9940090133 +15922 53.2567142704 -0.9901250263 +15923 53.2544534835 -0.9858311092 +15924 53.2524692693 -0.9811727603 +15925 53.2507826214 -0.9761993129 +15926 53.2494113829 -0.9709634145 +15927 53.2483700589 -0.9655204716 +15928 53.2476696632 -0.9599280663 +15929 53.2473176037 -0.9542453511 +15930 53.2473176037 -0.9485324267 +15931 53.2476696632 -0.9428497114 +15932 53.2483700589 -0.9372573062 +15933 53.2494113829 -0.9318143633 +15934 53.2507826214 -0.9265784649 +15935 53.2524692693 -0.9216050175 +15936 53.2544534835 -0.9169466686 +15937 53.2567142704 -0.9126527514 +15938 53.2592277065 -0.9087687645 +15939 53.2619671902 -0.9053358895 +15940 53.2649037226 -0.9023905548 +15941 53.2680062126 -0.8999640474 +15942 53.2712418052 -0.8980821786 +15943 53.2745762281 -0.8967650066 +15944 53.2779741546 -0.8960266194 +15945 53.2813995765 -0.8958749797 +15946 53.2848161856 -0.8963118354 +15947 53.2881877587 -0.8973326947 +15948 53.2914785415 -0.8989268679 +15949 53.2946536287 -0.9010775751 +15950 53.2976793342 -0.9037621194 +15951 53.3005235503 -0.9069521227 +15952 53.3031560887 -0.9106138235 +15953 53.3055490027 -0.9147084323 +15954 53.307676885 -0.9191925418 +15955 53.3095171386 -0.9240185872 +15956 53.3110502186 -0.9291353517 +15957 53.3122598403 -0.9344885119 +15958 53.3131331538 -0.9400212173 +15959 53.3136608811 -0.9456746971 +15960 53.3138374154 -0.9513888889 +15961 53.2331333333 -0.9799194444 +15962 53.2487633611 -0.9678115 +15963 53.2497798836 -0.9725227589 +15964 53.251046784 -0.9770623369 +15965 53.2525537778 -0.9813933333 +15966 53.2369222222 -0.9934972222 +15967 53.2331333333 -0.9799194444 +15968 53.3281666667 -0.9227055556 +15969 53.3123554722 -0.9349966667 +15970 53.3113403148 -0.9302773589 +15971 53.3100743476 -0.9257303104 +15972 53.3085678889 -0.9213926111 +15973 53.3243777778 -0.9090972222 +15974 53.3281666667 -0.9227055556 +15975 53.0566166392 -0.9116666667 +15976 53.0564400985 -0.9173467707 +15977 53.055912352 -0.9229665262 +15978 53.0550390067 -0.9284662302 +15979 53.0538293406 -0.9337874638 +15980 53.0522962039 -0.9388737164 +15981 53.0504558815 -0.9436709894 +15982 53.0483279189 -0.9481283718 +15983 53.0459349133 -0.9521985826 +15984 53.0433022727 -0.9558384733 +15985 53.0404579445 -0.959009485 +15986 53.0374321177 -0.961678057 +15987 53.0342569012 -0.9638159791 +15988 53.030965982 -0.9654006883 +15989 53.0275942667 -0.9664155033 +15990 53.0241775111 -0.9668497966 +15991 53.0207519397 -0.9666991014 +15992 53.0173538624 -0.9659651533 +15993 53.014019289 -0.9646558661 +15994 53.0107835481 -0.9627852422 +15995 53.0076809138 -0.9603732189 +15996 53.0047442428 -0.9574454526 +15997 53.0020046282 -0.9540330431 +15998 52.9994910706 -0.9501722013 +15999 52.9972301731 -0.9459038633 +16000 52.995245861 -0.9412732568 +16001 52.9935591292 -0.9363294217 +16002 52.9921878221 -0.9311246926 +16003 52.9911464456 -0.9257141471 +16004 52.9904460146 -0.9201550256 +16005 52.9900939372 -0.9145061296 +16006 52.9900939372 -0.9088272037 +16007 52.9904460146 -0.9031783077 +16008 52.9911464456 -0.8976191863 +16009 52.9921878221 -0.8922086407 +16010 52.9935591292 -0.8870039117 +16011 52.995245861 -0.8820600765 +16012 52.9972301731 -0.87742947 +16013 52.9994910706 -0.873161132 +16014 53.0020046282 -0.8693002902 +16015 53.0047442428 -0.8658878807 +16016 53.0076809138 -0.8629601145 +16017 53.0107835481 -0.8605480911 +16018 53.014019289 -0.8586774672 +16019 53.0173538624 -0.85736818 +16020 53.0207519397 -0.8566342319 +16021 53.0241775111 -0.8564835367 +16022 53.0275942667 -0.85691783 +16023 53.030965982 -0.8579326451 +16024 53.0342569012 -0.8595173543 +16025 53.0374321177 -0.8616552764 +16026 53.0404579445 -0.8643238483 +16027 53.0433022727 -0.8674948601 +16028 53.0459349133 -0.8711347507 +16029 53.0483279189 -0.8752049615 +16030 53.0504558815 -0.8796623439 +16031 53.0522962039 -0.8844596169 +16032 53.0538293406 -0.8895458695 +16033 53.0550390067 -0.8948671031 +16034 53.055912352 -0.9003668071 +16035 53.0564400985 -0.9059865626 +16036 53.0566166392 -0.9116666667 +16037 52.9757527778 -0.9462611111 +16038 52.9925465278 -0.9326351667 +16039 52.993814885 -0.9371605542 +16040 52.9953246472 -0.9414777553 +16041 52.9970634722 -0.9455515 +16042 52.9797083333 -0.9596277778 +16043 52.9757527778 -0.9462611111 +16044 53.069625 -0.8865611111 +16045 53.0555806111 -0.8979961667 +16046 53.0547037456 -0.8932158648 +16047 53.0535700163 -0.8885868653 +16048 53.0521887222 -0.8841471111 +16049 53.0656694444 -0.8731666667 +16050 53.069625 -0.8865611111 +16051 52.9761 -0.9445833333 +16052 52.9922667222 -0.9314683889 +16053 52.9934709154 -0.9360344626 +16054 52.9949186579 -0.9404020882 +16055 52.9965981667 -0.9445356667 +16056 52.9800527778 -0.9579527778 +16057 52.9761 -0.9445833333 +16058 53.0698027778 -0.8850333333 +16059 53.0553830278 -0.8967719444 +16060 53.0544416819 -0.8920324996 +16061 53.0532462932 -0.8874536336 +16062 53.0518066389 -0.8830727778 +16063 53.06585 -0.8716361111 +16064 53.0698027778 -0.8850333333 +16065 52.9947277778 -0.9864583333 +16066 53.0040936667 -0.9567 +16067 53.0066201301 -0.9593936936 +16068 53.0092827496 -0.9616990915 +16069 53.0120598611 -0.9635973611 +16070 53.0027 -0.9933361111 +16071 52.9947277778 -0.9864583333 +16072 53.0513527778 -0.8383527778 +16073 53.0425228056 -0.8665545278 +16074 53.0399925578 -0.8638693662 +16075 53.0373266633 -0.8615739082 +16076 53.0345468611 -0.8596867778 +16077 53.0433833333 -0.8314638889 +16078 53.0513527778 -0.8383527778 +16079 52.9957 -0.9851694444 +16080 53.0045089444 -0.9571801944 +16081 53.0070601033 -0.959810169 +16082 53.0097438645 -0.9620483698 +16083 53.0125383889 -0.9638765 +16084 53.0036722222 -0.9920472222 +16085 52.9957 -0.9851694444 +16086 53.0502083333 -0.8438194444 +16087 53.0429354444 -0.8670451944 +16088 53.0404299106 -0.8642959963 +16089 53.0377851374 -0.8619331102 +16090 53.0350226944 -0.8599757222 +16091 53.0422388889 -0.8369305556 +16092 53.0502083333 -0.8438194444 +16093 52.9948861111 -0.9844611111 +16094 53.0037530833 -0.9562944167 +16095 53.0062585353 -0.9590402789 +16096 53.0089030482 -0.961400833 +16097 53.0116651111 -0.9633568056 +16098 53.0028555556 -0.9913388889 +16099 52.9948861111 -0.9844611111 +16100 53.0487972222 -0.8450555556 +16101 53.0421849444 -0.8661643611 +16102 53.0396347292 -0.8635312747 +16103 53.0369517821 -0.8612906516 +16104 53.0341579722 -0.8594606944 +16105 53.0408277778 -0.8381666667 +16106 53.0487972222 -0.8450555556 +16107 53.0327916667 -0.9932277778 +16108 53.0274773611 -0.9664401111 +16109 53.0304427487 -0.9655974504 +16110 53.0333501353 -0.9643139209 +16111 53.03617575 -0.9625999167 +16112 53.041325 -0.9885555556 +16113 53.0327916667 -0.9932277778 +16114 53.0115861111 -0.8391277778 +16115 53.0153695556 -0.8580746667 +16116 53.0124841721 -0.8594877637 +16117 53.0096875054 -0.8613268855 +16118 53.0070023889 -0.8635769444 +16119 53.0030527778 -0.8437972222 +16120 53.0115861111 -0.8391277778 +16121 53.0334777778 -0.9937388889 +16122 53.0280407778 -0.9663150833 +16123 53.0309945302 -0.965389513 +16124 53.0338858783 -0.9640255096 +16125 53.0366912222 -0.9622341111 +16126 53.0420111111 -0.9890666667 +16127 53.0334777778 -0.9937388889 +16128 53.0106722222 -0.8315305556 +16129 53.0159266944 -0.8578550556 +16130 53.0130296541 -0.8591842718 +16131 53.0102167252 -0.8609412357 +16132 53.0075108333 -0.8631115556 +16133 53.0021388889 -0.8361972222 +16134 53.0106722222 -0.8315305556 +16135 53.0324972222 -0.9944416667 +16136 53.0269653611 -0.9665396667 +16137 53.029941211 -0.9657723513 +16138 53.0328630501 -0.9645618371 +16139 53.0357069444 -0.9629179722 +16140 53.0410305556 -0.9897694444 +16141 53.0324972222 -0.9944416667 +16142 53.0093083333 -0.8303138889 +16143 53.0148901944 -0.8582771389 +16144 53.0120150787 -0.8597627878 +16145 53.0092326862 -0.8616730086 +16146 53.0065657778 -0.8639921111 +16147 53.000775 -0.8349805556 +16148 53.0093083333 -0.8303138889 +16149 53.0658666667 -0.9541083333 +16150 53.0516073056 -0.9407998056 +16151 53.0530812795 -0.9364328997 +16152 53.054310836 -0.9318622098 +16153 53.0552858611 -0.9271253333 +16154 53.0702638889 -0.9411 +16155 53.0658666667 -0.9541083333 +16156 52.9829722222 -0.8598138889 +16157 52.9987451111 -0.8744734444 +16158 52.9968158968 -0.8783162842 +16159 52.995104339 -0.8824324816 +16160 52.9936244722 -0.8867882778 +16161 52.9785722222 -0.8727944444 +16162 52.9829722222 -0.8598138889 +16163 53.0651111111 -0.9523777778 +16164 53.0518878056 -0.9400369167 +16165 53.0533211891 -0.935623392 +16166 53.0545073484 -0.9310120734 +16167 53.0554365 -0.9262410278 +16168 53.0695083333 -0.9393694444 +16169 53.0651111111 -0.9523777778 +16170 52.9825083333 -0.8583611111 +16171 52.9991213611 -0.8738008056 +16172 52.9971507599 -0.8775965703 +16173 52.9953958037 -0.8816725553 +16174 52.9938709167 -0.8859951944 +16175 52.9781083333 -0.8713416667 +16176 52.9825083333 -0.8583611111 +16177 53.0653361111 -0.9546638889 +16178 53.0513138889 -0.94156925 +16179 53.0528294872 -0.9372483332 +16180 53.0541032867 -0.9327174011 +16181 53.0551248333 -0.9280136389 +16182 53.0697388889 -0.9416555556 +16183 53.0653361111 -0.9546638889 +16184 52.9836138889 -0.8614138889 +16185 52.9983811389 -0.8751460278 +16186 52.9964925478 -0.8790351997 +16187 52.9948236641 -0.8831911022 +16188 52.9933881389 -0.88757975 +16189 52.9792111111 -0.8743916667 +16190 52.9836138889 -0.8614138889 +16191 53.5930025171 -0.8583333333 +16192 53.5928259897 -0.8640851205 +16193 53.5922982831 -0.8697757947 +16194 53.5914250039 -0.8753448971 +16195 53.5902154301 -0.880733269 +16196 53.5886824113 -0.8858836849 +16197 53.5868422319 -0.8907414633 +16198 53.5847144365 -0.8952550498 +16199 53.5823216214 -0.8993765668 +16200 53.5796891934 -0.9030623216 +16201 53.5768450985 -0.9062732702 +16202 53.5738195239 -0.9089754301 +16203 53.5706445766 -0.9111402376 +16204 53.5673539412 -0.9127448481 +16205 53.5639825219 -0.913772373 +16206 53.5605660714 -0.9142120544 +16207 53.5571408114 -0.9140593727 +16208 53.5537430482 -0.9133160892 +16209 53.5504087882 -0.9119902209 +16210 53.5471733563 -0.91009595 +16211 53.5440710226 -0.907653468 +16212 53.5411346403 -0.9046887571 +16213 53.5383952985 -0.9012333109 +16214 53.5358819942 -0.8973237974 +16215 53.5336213271 -0.8930016694 +16216 53.531637219 -0.8883127239 +16217 53.5299506621 -0.8833066178 +16218 53.5285794981 -0.8780363436 +16219 53.5275382309 -0.8725576704 +16220 53.5268378737 -0.8669285573 +16221 53.5264858335 -0.8612085435 +16222 53.5264858335 -0.8554581231 +16223 53.5268378737 -0.8497381094 +16224 53.5275382309 -0.8441089963 +16225 53.5285794981 -0.8386303231 +16226 53.5299506621 -0.8333600489 +16227 53.531637219 -0.8283539428 +16228 53.5336213271 -0.8236649972 +16229 53.5358819942 -0.8193428692 +16230 53.5383952985 -0.8154333558 +16231 53.5411346403 -0.8119779095 +16232 53.5440710226 -0.8090131987 +16233 53.5471733563 -0.8065707167 +16234 53.5504087882 -0.8046764458 +16235 53.5537430482 -0.8033505775 +16236 53.5571408114 -0.802607294 +16237 53.5605660714 -0.8024546123 +16238 53.5639825219 -0.8028942936 +16239 53.5673539412 -0.8039218186 +16240 53.5706445766 -0.805526429 +16241 53.5738195239 -0.8076912366 +16242 53.5768450985 -0.8103933964 +16243 53.5796891934 -0.8136043451 +16244 53.5823216214 -0.8172900999 +16245 53.5847144365 -0.8214116168 +16246 53.5868422319 -0.8259252034 +16247 53.5886824113 -0.8307829817 +16248 53.5902154301 -0.8359333976 +16249 53.5914250039 -0.8413217696 +16250 53.5922982831 -0.8468908719 +16251 53.5928259897 -0.8525815462 +16252 53.5930025171 -0.8583333333 +16253 53.5216333333 -0.91055 +16254 53.5330525556 -0.8917588611 +16255 53.5349549572 -0.8956587241 +16256 53.537058912 -0.899255258 +16257 53.5393473333 -0.9025191667 +16258 53.5279277778 -0.9213083333 +16259 53.5216333333 -0.91055 +16260 53.5964805556 -0.8082888889 +16261 53.5864094444 -0.8249266389 +16262 53.5845080996 -0.8210211529 +16263 53.5824049166 -0.8174199324 +16264 53.5801170556 -0.8141522778 +16265 53.5901888889 -0.7975111111 +16266 53.5964805556 -0.8082888889 +16267 53.2077142103 -0.5238888889 +16268 53.207536568 -0.5302827139 +16269 53.207005161 -0.5366218315 +16270 53.2061245359 -0.5428520067 +16271 53.204902227 -0.5489199443 +16272 53.2033486911 -0.5547737486 +16273 53.2014772172 -0.5603633708 +16274 53.1993038121 -0.5656410391 +16275 53.1968470626 -0.5705616695 +16276 53.194127975 -0.5750832522 +16277 53.1911697949 -0.5791672108 +16278 53.1879978065 -0.582778732 +16279 53.1846391161 -0.5858870608 +16280 53.1811224189 -0.5884657617 +16281 53.1774777527 -0.5904929406 +16282 53.1737362408 -0.5919514285 +16283 53.1699298254 -0.5928289237 +16284 53.1660909943 -0.5931180914 +16285 53.1622525033 -0.5928166217 +16286 53.1584470964 -0.5919272434 +16287 53.1547072272 -0.5904576959 +16288 53.1510647819 -0.5884206578 +16289 53.1475508082 -0.5858336336 +16290 53.1441952511 -0.5827188008 +16291 53.1410266992 -0.5791028166 +16292 53.1380721416 -0.5750165877 +16293 53.1353567393 -0.5704950051 +16294 53.1329036124 -0.5655766448 +16295 53.1307336437 -0.5603034396 +16296 53.1288653031 -0.5547203213 +16297 53.1273144907 -0.5488748403 +16298 53.1260944027 -0.542816762 +16299 53.1252154203 -0.5365976464 +16300 53.1246850218 -0.5302704118 +16301 53.1245077195 -0.5238888889 +16302 53.1246850218 -0.517507366 +16303 53.1252154203 -0.5111801314 +16304 53.1260944027 -0.5049610157 +16305 53.1273144907 -0.4989029375 +16306 53.1288653031 -0.4930574565 +16307 53.1307336437 -0.4874743382 +16308 53.1329036124 -0.4822011329 +16309 53.1353567393 -0.4772827727 +16310 53.1380721416 -0.4727611901 +16311 53.1410266992 -0.4686749612 +16312 53.1441952511 -0.465058977 +16313 53.1475508082 -0.4619441442 +16314 53.1510647819 -0.45935712 +16315 53.1547072272 -0.4573200818 +16316 53.1584470964 -0.4558505344 +16317 53.1622525033 -0.4549611561 +16318 53.1660909943 -0.4546596863 +16319 53.1699298254 -0.4549488541 +16320 53.1737362408 -0.4558263492 +16321 53.1774777527 -0.4572848372 +16322 53.1811224189 -0.4593120161 +16323 53.1846391161 -0.4618907169 +16324 53.1879978065 -0.4649990458 +16325 53.1911697949 -0.468610567 +16326 53.194127975 -0.4726945256 +16327 53.1968470626 -0.4772161083 +16328 53.1993038121 -0.4821367386 +16329 53.2014772172 -0.487414407 +16330 53.2033486911 -0.4930040291 +16331 53.204902227 -0.4988578335 +16332 53.2061245359 -0.504925771 +16333 53.207005161 -0.5111559462 +16334 53.207536568 -0.5174950639 +16335 53.2077142103 -0.5238888889 +16336 53.1109521111 -0.5523125556 +16337 53.1260178611 -0.54236325 +16338 53.1269222092 -0.5471194495 +16339 53.1280302058 -0.5517551548 +16340 53.1293361111 -0.5562463056 +16341 53.1142725833 -0.5661892778 +16342 53.1109521111 -0.5523125556 +16343 53.2203266667 -0.4960258889 +16344 53.2062031111 -0.5053914167 +16345 53.2052975907 -0.5006270692 +16346 53.2041880917 -0.4959840364 +16347 53.2028803889 -0.4914865278 +16348 53.21700625 -0.4821149167 +16349 53.2203266667 -0.4960258889 +16350 53.0713373914 -0.4927527778 +16351 53.0711597458 -0.4991263854 +16352 53.070628329 -0.5054454595 +16353 53.0697476878 -0.5116559371 +16354 53.0685253563 -0.5177046922 +16355 53.0669717913 -0.523539994 +16356 53.0651002821 -0.5291119522 +16357 53.0629268355 -0.5343729466 +16358 53.0604700383 -0.5392780356 +16359 53.0577508973 -0.5437853424 +16360 53.054792658 -0.5478564126 +16361 53.0516206051 -0.5514565422 +16362 53.0482618451 -0.5545550733 +16363 53.0447450735 -0.557125653 +16364 53.0411003288 -0.5591464559 +16365 53.0373587348 -0.5606003663 +16366 53.0335522342 -0.5614751202 +16367 53.0297133154 -0.5617634053 +16368 53.025874735 -0.5614629176 +16369 53.0220692379 -0.5605763766 +16370 53.0183292784 -0.559111496 +16371 53.0146867436 -0.5570809135 +16372 53.011172682 -0.5545020777 +16373 53.0078170398 -0.5513970952 +16374 53.0046484063 -0.5477925386 +16375 53.0016937715 -0.5437192166 +16376 52.9989782975 -0.5392119097 +16377 52.996525105 -0.5343090725 +16378 52.9943550778 -0.5290525052 +16379 52.9924866863 -0.5234869983 +16380 52.9909358313 -0.5176599526 +16381 52.9897157097 -0.5116209771 +16382 52.988836703 -0.5054214697 +16383 52.9883062898 -0.4991141827 +16384 52.9881289825 -0.4927527778 +16385 52.9883062898 -0.4863913728 +16386 52.988836703 -0.4800840859 +16387 52.9897157097 -0.4738845785 +16388 52.9909358313 -0.467845603 +16389 52.9924866863 -0.4620185572 +16390 52.9943550778 -0.4564530504 +16391 52.996525105 -0.4511964831 +16392 52.9989782975 -0.4462936458 +16393 53.0016937715 -0.441786339 +16394 53.0046484063 -0.437713017 +16395 53.0078170398 -0.4341084603 +16396 53.011172682 -0.4310034778 +16397 53.0146867436 -0.428424642 +16398 53.0183292784 -0.4263940595 +16399 53.0220692379 -0.424929179 +16400 53.025874735 -0.424042638 +16401 53.0297133154 -0.4237421503 +16402 53.0335522342 -0.4240304353 +16403 53.0373587348 -0.4249051893 +16404 53.0411003288 -0.4263590997 +16405 53.0447450735 -0.4283799025 +16406 53.0482618451 -0.4309504822 +16407 53.0516206051 -0.4340490133 +16408 53.054792658 -0.437649143 +16409 53.0577508973 -0.4417202131 +16410 53.0604700383 -0.4462275199 +16411 53.0629268355 -0.451132609 +16412 53.0651002821 -0.4563936033 +16413 53.0669717913 -0.4619655615 +16414 53.0685253563 -0.4678008634 +16415 53.0697476878 -0.4738496185 +16416 53.070628329 -0.4800600961 +16417 53.0711597458 -0.4863791702 +16418 53.0713373914 -0.4927527778 +16419 52.9759416667 -0.4886638889 +16420 52.9883466944 -0.4857053333 +16421 52.9881471692 -0.4907135656 +16422 52.9881678233 -0.4957325729 +16423 52.9884085556 -0.5007358333 +16424 52.9772222222 -0.5034 +16425 52.9759416667 -0.4886638889 +16426 53.0791638889 -0.4790694444 +16427 53.0707389722 -0.4810846389 +16428 53.0701185314 -0.4761629955 +16429 53.0692838807 -0.4713295119 +16430 53.0682394722 -0.4666098611 +16431 53.0778833333 -0.4643 +16432 53.0791638889 -0.4790694444 +16433 53.0185333333 -0.5786777778 +16434 53.0200006389 -0.559841 +16435 53.0229411873 -0.5608322154 +16436 53.0259171598 -0.5614694696 +16437 53.0289130833 -0.5617493611 +16438 53.0274472222 -0.5805666667 +16439 53.0185333333 -0.5786777778 +16440 53.0409472222 -0.4057472222 +16441 53.0394249444 -0.4256331389 +16442 53.0364830877 -0.4246510812 +16443 53.0335062108 -0.4240234784 +16444 53.0305098056 -0.4237535278 +16445 53.0320333333 -0.40385 +16446 53.0409472222 -0.4057472222 +16447 53.01855 -0.5711777778 +16448 53.0194088611 -0.55959675 +16449 53.022340648 -0.560659422 +16450 53.025310992 -0.5613689532 +16451 53.0283044444 -0.5617215833 +16452 53.0274694444 -0.5729805556 +16453 53.01855 -0.5711777778 +16454 53.039175 -0.4137722222 +16455 53.0383400278 -0.4252282222 +16456 53.0353831851 -0.4243769461 +16457 53.0323970413 -0.4238815851 +16458 53.0293971389 -0.4237446389 +16459 53.0302555556 -0.4119666667 +16460 53.039175 -0.4137722222 +16461 53.0167546667 -0.5643539444 +16462 53.0182818889 -0.559089 +16463 53.0213150389 -0.56032936 +16464 53.0243957527 -0.5611889152 +16465 53.0275066667 -0.56166275 +16466 53.0248561111 -0.5708006667 +16467 53.0167546667 -0.5643539444 +16468 53.0683875833 -0.4202738333 +16469 53.0607521667 -0.4467458333 +16470 53.0585835142 -0.4430133857 +16471 53.0562521411 -0.439561951 +16472 53.0537712222 -0.4364109722 +16473 53.0602862222 -0.4138206111 +16474 53.0683875833 -0.4202738333 +16475 53.08874525 -0.4558644444 +16476 53.0698336944 -0.4743584167 +16477 53.0689181653 -0.4695525918 +16478 53.0677938034 -0.4648706423 +16479 53.0664666111 -0.4603375556 +16480 53.0841885 -0.4430011389 +16481 53.08874525 -0.4558644444 +16482 53.6150307992 -0.3514583333 +16483 53.6148531665 -0.3579135341 +16484 53.6143217883 -0.3643135 +16485 53.6134412113 -0.370603473 +16486 53.6122189696 -0.3767296443 +16487 53.6106655197 -0.3826396183 +16488 53.6087941506 -0.3882828644 +16489 53.6066208689 -0.3936111511 +16490 53.6041642607 -0.3985789612 +16491 53.601445332 -0.4031438817 +16492 53.5984873276 -0.4072669666 +16493 53.5953155311 -0.4109130692 +16494 53.5919570477 -0.4140511412 +16495 53.5884405714 -0.4166544952 +16496 53.5847961387 -0.4187010295 +16497 53.5810548714 -0.4201734131 +16498 53.5772487098 -0.4210592292 +16499 53.5734101397 -0.4213510757 +16500 53.5695719148 -0.4210466237 +16501 53.5657667769 -0.4201486315 +16502 53.5620271769 -0.4186649156 +16503 53.5583849984 -0.4166082789 +16504 53.5548712864 -0.4139963963 +16505 53.5515159834 -0.41085166 +16506 53.5483476749 -0.4072009842 +16507 53.5453933474 -0.4030755731 +16508 53.5426781594 -0.3985106526 +16509 53.5402252281 -0.3935451687 +16510 53.5380554343 -0.388221455 +16511 53.5361872456 -0.3825848733 +16512 53.5346365601 -0.3766834279 +16513 53.5334165726 -0.3705673591 +16514 53.5325376629 -0.3642887183 +16515 53.5320073084 -0.3579009286 +16516 53.5318300209 -0.3514583333 +16517 53.5320073084 -0.3450157381 +16518 53.5325376629 -0.3386279483 +16519 53.5334165726 -0.3323493076 +16520 53.5346365601 -0.3262332388 +16521 53.5361872456 -0.3203317933 +16522 53.5380554343 -0.3146952116 +16523 53.5402252281 -0.309371498 +16524 53.5426781594 -0.304406014 +16525 53.5453933474 -0.2998410935 +16526 53.5483476749 -0.2957156825 +16527 53.5515159834 -0.2920650067 +16528 53.5548712864 -0.2889202703 +16529 53.5583849984 -0.2863083878 +16530 53.5620271769 -0.284251751 +16531 53.5657667769 -0.2827680351 +16532 53.5695719148 -0.2818700429 +16533 53.5734101397 -0.281565591 +16534 53.5772487098 -0.2818574375 +16535 53.5810548714 -0.2827432535 +16536 53.5847961387 -0.2842156372 +16537 53.5884405714 -0.2862621715 +16538 53.5919570477 -0.2888655254 +16539 53.5953155311 -0.2920035974 +16540 53.5984873276 -0.2956497001 +16541 53.601445332 -0.299772785 +16542 53.6041642607 -0.3043377054 +16543 53.6066208689 -0.3093055156 +16544 53.6087941506 -0.3146338023 +16545 53.6106655197 -0.3202770483 +16546 53.6122189696 -0.3261870224 +16547 53.6134412113 -0.3323131937 +16548 53.6143217883 -0.3386031667 +16549 53.6148531665 -0.3450031326 +16550 53.6150307992 -0.3514583333 +16551 53.5220722222 -0.3787722222 +16552 53.5334741944 -0.3709044722 +16553 53.5344122774 -0.3756882022 +16554 53.5355531468 -0.380346243 +16555 53.5368908889 -0.3848544167 +16556 53.5254916667 -0.3927166667 +16557 53.5220722222 -0.3787722222 +16558 53.6247805556 -0.3240805556 +16559 53.6133836944 -0.33197675 +16560 53.6124439859 -0.3271853186 +16561 53.6113011963 -0.32252048 +16562 53.6099612778 -0.3180065556 +16563 53.6213638889 -0.3101027778 +16564 53.6247805556 -0.3240805556 +16565 53.5654611111 -0.4272916667 +16566 53.5660261111 -0.4202290833 +16567 53.5690011489 -0.420950153 +16568 53.5719994114 -0.4213085477 +16569 53.57500525 -0.4213023056 +16570 53.5743666667 -0.4292833333 +16571 53.5654611111 -0.4272916667 +16572 53.587075 -0.2691388889 +16573 53.5858466111 -0.2847413611 +16574 53.5829460348 -0.2834108694 +16575 53.5799958388 -0.2824360879 +16576 53.5770114444 -0.2818220278 +16577 53.5781666667 -0.2671444444 +16578 53.587075 -0.2691388889 +16579 53.3502177668 -0.3487972222 +16580 53.3500412334 -0.3545162778 +16581 53.3495135088 -0.3601745694 +16582 53.3486401997 -0.3657119835 +16583 53.3474305843 -0.371069699 +16584 53.3458975123 -0.376190817 +16585 53.3440572683 -0.3810209678 +16586 53.3419293974 -0.3855088908 +16587 53.3395364964 -0.3896069807 +16588 53.3369039724 -0.3932717934 +16589 53.3340597721 -0.3964645064 +16590 53.3310340837 -0.3991513297 +16591 53.3278590148 -0.4013038611 +16592 53.3245682512 -0.4028993846 +16593 53.3211966981 -0.4039211062 +16594 53.3177801097 -0.4043583275 +16595 53.314354709 -0.4042065531 +16596 53.3109568038 -0.4034675324 +16597 53.3076224021 -0.4021492354 +16598 53.3043868305 -0.4002657622 +16599 53.3012843609 -0.3978371881 +16600 53.2983478481 -0.3948893467 +16601 53.2956083828 -0.3914535517 +16602 53.293094964 -0.3875662623 +16603 53.2908341927 -0.3832686955 +16604 53.2888499923 -0.3786063882 +16605 53.2871633562 -0.3736287158 +16606 53.2857921275 -0.3683883701 +16607 53.2847508108 -0.3629408047 +16608 53.2840504202 -0.3573436505 +16609 53.2836983632 -0.3516561099 +16610 53.2836983632 -0.3459383346 +16611 53.2840504202 -0.3402507939 +16612 53.2847508108 -0.3346536397 +16613 53.2857921275 -0.3292060743 +16614 53.2871633562 -0.3239657287 +16615 53.2888499923 -0.3189880562 +16616 53.2908341927 -0.3143257489 +16617 53.293094964 -0.3100281821 +16618 53.2956083828 -0.3061408928 +16619 53.2983478481 -0.3027050977 +16620 53.3012843609 -0.2997572563 +16621 53.3043868305 -0.2973286823 +16622 53.3076224021 -0.295445209 +16623 53.3109568038 -0.294126912 +16624 53.314354709 -0.2933878914 +16625 53.3177801097 -0.2932361169 +16626 53.3211966981 -0.2936733382 +16627 53.3245682512 -0.2946950599 +16628 53.3278590148 -0.2962905833 +16629 53.3310340837 -0.2984431148 +16630 53.3340597721 -0.301129938 +16631 53.3369039724 -0.3043226511 +16632 53.3395364964 -0.3079874638 +16633 53.3419293974 -0.3120855537 +16634 53.3440572683 -0.3165734767 +16635 53.3458975123 -0.3214036274 +16636 53.3474305843 -0.3265247454 +16637 53.3486401997 -0.331882461 +16638 53.3495135088 -0.337419875 +16639 53.3500412334 -0.3430781667 +16640 53.3502177668 -0.3487972222 +16641 53.2722333333 -0.3756833333 +16642 53.2851925278 -0.3654925278 +16643 53.2862230041 -0.3702002326 +16644 53.2875034333 -0.374734012 +16645 53.2890234167 -0.379057 +16646 53.2760666667 -0.3892416667 +16647 53.2722333333 -0.3756833333 +16648 53.361625 -0.3218611111 +16649 53.3486772222 -0.3320773056 +16650 53.3476452269 -0.32736351 +16651 53.3463629732 -0.3228246477 +16652 53.3448409167 -0.31849775 +16653 53.3577916667 -0.308275 +16654 53.361625 -0.3218611111 +16655 53.3559444444 -0.3958777778 +16656 53.3429619167 -0.3834495556 +16657 53.3447268267 -0.3793878275 +16658 53.3462652363 -0.3750764222 +16659 53.3475645833 -0.3705505 +16660 53.3604055556 -0.3828388889 +16661 53.3559444444 -0.3958777778 +16662 53.2785583333 -0.3046611111 +16663 53.2901840278 -0.3157443333 +16664 53.2885084906 -0.3199044072 +16665 53.2870643575 -0.3242993329 +16666 53.2858633611 -0.3288933611 +16667 53.2740972222 -0.3176722222 +16668 53.2785583333 -0.3046611111 +16669 53.1346591682 -0.1661111111 +16670 53.1344815242 -0.1724940855 +16671 53.1339501119 -0.1788224458 +16672 53.1330694782 -0.1850420493 +16673 53.1318471572 -0.1910996917 +16674 53.1302936057 -0.1969435658 +16675 53.1284221129 -0.2025237078 +16676 53.1262486856 -0.2077924272 +16677 53.1237919106 -0.2127047167 +16678 53.1210727944 -0.2172186375 +16679 53.1181145826 -0.2212956789 +16680 53.1149425597 -0.2249010863 +16681 53.111583832 -0.2280041568 +16682 53.108067095 -0.230578499 +16683 53.1044223867 -0.2326022559 +16684 53.1006808309 -0.2340582872 +16685 53.0968743699 -0.2349343111 +16686 53.0930354918 -0.2352230051 +16687 53.0891969529 -0.2349220625 +16688 53.0853914977 -0.234034207 +16689 53.0816515802 -0.2325671642 +16690 53.0780090869 -0.2305335908 +16691 53.0744950661 -0.2279509613 +16692 53.0711394634 -0.2248414152 +16693 53.0679708678 -0.2212315641 +16694 53.0650162689 -0.2171522623 +16695 53.0623008282 -0.2126383414 +16696 53.0598476661 -0.2077283123 +16697 53.0576776661 -0.2024640366 +16698 53.0558092983 -0.1968903703 +16699 53.054258463 -0.1910547834 +16700 53.053038357 -0.1850069576 +16701 53.0521593616 -0.1787983656 +16702 53.0516289552 -0.1724818368 +16703 53.0514516503 -0.1661111111 +16704 53.0516289552 -0.1597403854 +16705 53.0521593616 -0.1534238567 +16706 53.053038357 -0.1472152647 +16707 53.054258463 -0.1411674388 +16708 53.0558092983 -0.1353318519 +16709 53.0576776661 -0.1297581856 +16710 53.0598476661 -0.1244939099 +16711 53.0623008282 -0.1195838808 +16712 53.0650162689 -0.1150699599 +16713 53.0679708678 -0.1109906581 +16714 53.0711394634 -0.1073808071 +16715 53.0744950661 -0.1042712609 +16716 53.0780090869 -0.1016886314 +16717 53.0816515802 -0.099655058 +16718 53.0853914977 -0.0981880153 +16719 53.0891969529 -0.0973001597 +16720 53.0930354918 -0.0969992171 +16721 53.0968743699 -0.0972879111 +16722 53.1006808309 -0.0981639351 +16723 53.1044223867 -0.0996199663 +16724 53.108067095 -0.1016437232 +16725 53.111583832 -0.1042180655 +16726 53.1149425597 -0.1073211359 +16727 53.1181145826 -0.1109265433 +16728 53.1210727944 -0.1150035847 +16729 53.1237919106 -0.1195175056 +16730 53.1262486856 -0.124429795 +16731 53.1284221129 -0.1296985144 +16732 53.1302936057 -0.1352786564 +16733 53.1318471572 -0.1411225305 +16734 53.1330694782 -0.1471801729 +16735 53.1339501119 -0.1533997764 +16736 53.1344815242 -0.1597281367 +16737 53.1346591682 -0.1661111111 +16738 53.0711036389 -0.2541946667 +16739 53.0760418333 -0.2291673333 +16740 53.0788218642 -0.2310417153 +16741 53.0816759933 -0.2325787151 +16742 53.0845893889 -0.2337702778 +16743 53.0796456944 -0.2588251667 +16744 53.0711036389 -0.2541946667 +16745 53.1151844722 -0.0779853056 +16746 53.11025525 -0.1031692778 +16747 53.1074797611 -0.1012750652 +16748 53.104629315 -0.0997184131 +16749 53.10171875 -0.0985073611 +16750 53.1066424722 -0.0733509722 +16751 53.1151844722 -0.0779853056 +16752 53.2925819792 -4.3740111111 +16753 53.2924054444 -4.3797224662 +16754 53.2918777155 -4.3853731395 +16755 53.2910043994 -4.3909030984 +16756 53.289794774 -4.3962536017 +16757 53.2882616893 -4.4013678271 +16758 53.28642143 -4.4061914781 +16759 53.2842935411 -4.4106733634 +16760 53.2819006196 -4.4147659418 +16761 53.2792680728 -4.4184258276 +16762 53.2764238474 -4.4216142504 +16763 53.2733981319 -4.4242974655 +16764 53.2702230341 -4.4264471089 +16765 53.2669322399 -4.4280404944 +16766 53.2635606551 -4.4290608507 +16767 53.2601440339 -4.4294974932 +16768 53.2567185997 -4.4293459322 +16769 53.2533206608 -4.4286079143 +16770 53.2499862254 -4.4272913986 +16771 53.2467506206 -4.4254104656 +16772 53.2436481187 -4.4229851635 +16773 53.2407115749 -4.4200412909 +16774 53.2379720803 -4.416610119 +16775 53.2354586342 -4.4127280581 +16776 53.2331978382 -4.4084362697 +16777 53.2312136158 -4.4037802294 +16778 53.229526961 -4.3988092463 +16779 53.2281557169 -4.3935759418 +16780 53.2271143885 -4.388135695 +16781 53.2264139899 -4.3825460595 +16782 53.226061929 -4.3768661586 +16783 53.226061929 -4.3711560636 +16784 53.2264139899 -4.3654761627 +16785 53.2271143885 -4.3598865272 +16786 53.2281557169 -4.3544462804 +16787 53.229526961 -4.3492129759 +16788 53.2312136158 -4.3442419928 +16789 53.2331978382 -4.3395859526 +16790 53.2354586342 -4.3352941641 +16791 53.2379720803 -4.3314121032 +16792 53.2407115749 -4.3279809314 +16793 53.2436481187 -4.3250370587 +16794 53.2467506206 -4.3226117567 +16795 53.2499862254 -4.3207308237 +16796 53.2533206608 -4.3194143079 +16797 53.2567185997 -4.3186762901 +16798 53.2601440339 -4.318524729 +16799 53.2635606551 -4.3189613715 +16800 53.2669322399 -4.3199817278 +16801 53.2702230341 -4.3215751134 +16802 53.2733981319 -4.3237247567 +16803 53.2764238474 -4.3264079718 +16804 53.2792680728 -4.3295963947 +16805 53.2819006196 -4.3332562804 +16806 53.2842935411 -4.3373488588 +16807 53.28642143 -4.3418307441 +16808 53.2882616893 -4.3466543951 +16809 53.289794774 -4.3517686205 +16810 53.2910043994 -4.3571191238 +16811 53.2918777155 -4.3626490828 +16812 53.2924054444 -4.3682997561 +16813 53.2925819792 -4.3740111111 +16814 53.2153488889 -4.4203648889 +16815 53.2303406667 -4.40135675 +16816 53.2319366862 -4.4055967384 +16817 53.2337554082 -4.4095800249 +16818 53.2357820556 -4.4132741944 +16819 53.2207938056 -4.4322736944 +16820 53.2153488889 -4.4203648889 +16821 53.3035637222 -4.3271375 +16822 53.2882521389 -4.34662625 +16823 53.2866539207 -4.3423830117 +16824 53.2848328586 -4.3383978058 +16825 53.2828038056 -4.3347031111 +16826 53.2981188889 -4.3152056667 +16827 53.3035637222 -4.3271375 +16828 53.4670833333 -2.93805 +16829 53.4648444444 -2.9446055556 +16830 53.4612333333 -2.9447194444 +16831 53.4572638889 -2.9432222222 +16832 53.4570138889 -2.9298333333 +16833 53.4595444444 -2.9254722222 +16834 53.4641 -2.9268444444 +16835 53.46705 -2.9333222222 +16836 53.4670833333 -2.93805 +16837 53.9308583333 -1.1900611111 +16838 53.9275305556 -1.1936361111 +16839 53.9222666667 -1.1895888889 +16840 53.9211972222 -1.1848388889 +16841 53.9221 -1.1794583333 +16842 53.9269861111 -1.1751583333 +16843 53.9311083333 -1.1780777778 +16844 53.9308583333 -1.1900611111 +16845 53.0424444444 -2.927375 +16846 53.0330111111 -2.9403833333 +16847 53.0268944444 -2.9270166667 +16848 53.0362027778 -2.9147805556 +16849 53.0424444444 -2.927375 +16850 53.6402944444 -2.154525 +16851 53.6327444444 -2.1525222222 +16852 53.6288722222 -2.1448333333 +16853 53.6317027778 -2.1377555556 +16854 53.6348333333 -2.1370972222 +16855 53.6406194444 -2.1397833333 +16856 53.6402944444 -2.154525 +16857 53.5315583333 -1.1444388889 +16858 53.5239944444 -1.1577666667 +16859 53.5177194444 -1.1453638889 +16860 53.5251083333 -1.1354083333 +16861 53.5315583333 -1.1444388889 +16862 53.5202 -2.3030138889 +16863 53.5156833333 -2.3129333333 +16864 53.5080277778 -2.3022722222 +16865 53.5130083333 -2.2917777778 +16866 53.5171638889 -2.2921805556 +16867 53.5202 -2.3030138889 +16868 53.9896138889 -0.8760472222 +16869 53.979075 -0.8775861111 +16870 53.9782 -0.8606055556 +16871 53.9888222222 -0.8593111111 +16872 53.9896138889 -0.8760472222 +16873 53.6854666667 -2.7676833333 +16874 53.6757666667 -2.7675444444 +16875 53.6728833333 -2.7581694444 +16876 53.6731444444 -2.7399944444 +16877 53.6841611111 -2.7410666667 +16878 53.6856027778 -2.7487361111 +16879 53.6854666667 -2.7676833333 +16880 53.5242805556 -2.5694444444 +16881 53.5218611111 -2.5862361111 +16882 53.5132916667 -2.5829361111 +16883 53.5157472222 -2.5656388889 +16884 53.5242805556 -2.5694444444 +16885 53.7549277778 -0.3041611111 +16886 53.7440388889 -0.3046055556 +16887 53.74415 -0.2920833333 +16888 53.7494888889 -0.2857472222 +16889 53.7550638889 -0.2854222222 +16890 53.7549277778 -0.3041611111 +16891 53.7757222222 -0.6382388889 +16892 53.7714277778 -0.6510861111 +16893 53.7639166667 -0.6461416667 +16894 53.7635388889 -0.6329944444 +16895 53.7680166667 -0.6240388889 +16896 53.7741194444 -0.6313444444 +16897 53.7757222222 -0.6382388889 +16898 53.8012805556 -1.5773277778 +16899 53.8002944444 -1.5836694444 +16900 53.7941166667 -1.5858305556 +16901 53.7907694444 -1.5771444444 +16902 53.7924361111 -1.5686861111 +16903 53.7994833333 -1.5694972222 +16904 53.8012805556 -1.5773277778 +16905 53.24055 -0.5207194444 +16906 53.2375583333 -0.5256916667 +16907 53.2337277778 -0.5254333333 +16908 53.2314527778 -0.5227 +16909 53.2306444444 -0.5127777778 +16910 53.2332305556 -0.5089916667 +16911 53.2393777778 -0.5106 +16912 53.24055 -0.5207194444 +16913 53.5535833333 -0.9806055556 +16914 53.5387166667 -0.9814833333 +16915 53.5372694444 -0.9591083333 +16916 53.5484222222 -0.9536722222 +16917 53.5530611111 -0.9588222222 +16918 53.5535833333 -0.9806055556 +16919 53.4611777778 -2.9800194444 +16920 53.4516722222 -2.9762333333 +16921 53.4552138889 -2.9585833333 +16922 53.4616583333 -2.9614138889 +16923 53.4638861111 -2.9647527778 +16924 53.4611777778 -2.9800194444 +16925 53.0207638889 -1.0387222222 +16926 53.0188944444 -1.04635 +16927 53.0145166667 -1.0495444444 +16928 53.0096305556 -1.0426388889 +16929 53.010775 -1.0340305556 +16930 53.0151972222 -1.0301833333 +16931 53.019425 -1.0323027778 +16932 53.0207638889 -1.0387222222 +16933 53.5000555556 -2.2525083333 +16934 53.4935416667 -2.2556861111 +16935 53.4887888889 -2.2519944444 +16936 53.4877444444 -2.2465805556 +16937 53.4886138889 -2.242975 +16938 53.4915083333 -2.2370361111 +16939 53.4954055556 -2.2373111111 +16940 53.4992083333 -2.246225 +16941 53.5000555556 -2.2525083333 +16942 53.1738 -0.6910888889 +16943 53.1687666667 -0.6956666667 +16944 53.1615611111 -0.6930166667 +16945 53.1605805556 -0.6816 +16946 53.1627138889 -0.6761861111 +16947 53.1725222222 -0.6785611111 +16948 53.1738 -0.6910888889 +16949 53.6405861111 -1.6165638889 +16950 53.6384694444 -1.6218666667 +16951 53.6332194444 -1.6211555556 +16952 53.6311361111 -1.6110805556 +16953 53.6312833333 -1.6048611111 +16954 53.6364944444 -1.6036416667 +16955 53.6405777778 -1.6056888889 +16956 53.6405861111 -1.6165638889 +16957 53.7683555556 -2.6846 +16958 53.7653888889 -2.6940861111 +16959 53.7606694444 -2.6968777778 +16960 53.7569972222 -2.6900666667 +16961 53.760175 -2.6785833333 +16962 53.7683555556 -2.6846 +16963 53.3286666667 -0.9960666667 +16964 53.3238277778 -1.009525 +16965 53.3174138889 -1.0096972222 +16966 53.3160194444 -0.9902694444 +16967 53.3227777778 -0.9887527778 +16968 53.3286666667 -0.9960666667 +16969 53.4438638889 -2.5262638889 +16970 53.4401555556 -2.5317916667 +16971 53.4327611111 -2.5344305556 +16972 53.4338666667 -2.5137916667 +16973 53.4399416667 -2.5162555556 +16974 53.443075 -2.5190416667 +16975 53.4438638889 -2.5262638889 +16976 53.3452222222 -2.2365972222 +16977 53.3438305556 -2.2448416667 +16978 53.3386916667 -2.2500166667 +16979 53.3347666667 -2.2451083333 +16980 53.3360222222 -2.2324833333 +16981 53.3418388889 -2.2282388889 +16982 53.3452222222 -2.2365972222 +16983 53.6866277778 -1.5180833333 +16984 53.6818027778 -1.5176888889 +16985 53.67625 -1.511725 +16986 53.6807305556 -1.4965 +16987 53.6883444444 -1.5075333333 +16988 53.6866277778 -1.5180833333 +16989 53.9221611111 -1.33255 +16990 53.9183027778 -1.3364861111 +16991 53.9151166667 -1.3382055556 +16992 53.9119583333 -1.3392722222 +16993 53.9089 -1.3319944444 +16994 53.9087638889 -1.3256611111 +16995 53.9155222222 -1.3190305556 +16996 53.9207194444 -1.3214888889 +16997 53.9221611111 -1.33255 +16998 53.0264583333 -2.0938416667 +16999 53.0216055556 -2.094375 +17000 53.0165722222 -2.0916583333 +17001 53.0187611111 -2.0768916667 +17002 53.0252555556 -2.0805333333 +17003 53.0276388889 -2.0854083333 +17004 53.0264583333 -2.0938416667 +17005 53.9410944444 -1.3716555556 +17006 53.9397888889 -1.3724861111 +17007 53.9377611111 -1.3780666667 +17008 53.9308861111 -1.3747638889 +17009 53.9324555556 -1.3567138889 +17010 53.9424916667 -1.3605833333 +17011 53.9410944444 -1.3716555556 +17012 54.4319645097 -7.6518944444 +17013 54.4317880028 -7.6577631133 +17014 54.4312603575 -7.6635694228 +17015 54.4303871803 -7.6692516811 +17016 54.4291777486 -7.6747495237 +17017 54.4276449115 -7.680004559 +17018 54.4258049525 -7.6849609919 +17019 54.423677415 -7.6895662193 +17020 54.4212848941 -7.6937713903 +17021 54.4186527945 -7.6975319255 +17022 54.4158090603 -7.7008079893 +17023 54.4127838759 -7.7035649119 +17024 54.4096093453 -7.7057735534 +17025 54.4063191496 -7.7074106097 +17026 54.4029481892 -7.7084588548 +17027 54.3995322122 -7.7089073179 +17028 54.3961074356 -7.7087513939 +17029 54.3927101604 -7.7079928858 +17030 54.3893763876 -7.7066399793 +17031 54.3861414363 -7.7047071497 +17032 54.3830395707 -7.7022150032 +17033 54.380103638 -7.6991900532 +17034 54.3773647213 -7.6956644351 +17035 54.3748518119 -7.691675563 +17036 54.372591504 -7.6872657315 +17037 54.3706077142 -7.6824816662 +17038 54.3689214302 -7.6773740298 +17039 54.3675504896 -7.6719968874 +17040 54.366509393 -7.6664071357 +17041 54.3658091509 -7.6606639053 +17042 54.3654571688 -7.6548279383 +17043 54.3654571688 -7.6489609506 +17044 54.3658091509 -7.6431249836 +17045 54.366509393 -7.6373817532 +17046 54.3675504896 -7.6317920015 +17047 54.3689214302 -7.626414859 +17048 54.3706077142 -7.6213072227 +17049 54.372591504 -7.6165231574 +17050 54.3748518119 -7.6121133258 +17051 54.3773647213 -7.6081244538 +17052 54.380103638 -7.6045988357 +17053 54.3830395707 -7.6015738857 +17054 54.3861414363 -7.5990817392 +17055 54.3893763876 -7.5971489096 +17056 54.3927101604 -7.595796003 +17057 54.3961074356 -7.5950374949 +17058 54.3995322122 -7.594881571 +17059 54.4029481892 -7.5953300341 +17060 54.4063191496 -7.5963782792 +17061 54.4096093453 -7.5980153355 +17062 54.4127838759 -7.600223977 +17063 54.4158090603 -7.6029808996 +17064 54.4186527945 -7.6062569634 +17065 54.4212848941 -7.6100174985 +17066 54.423677415 -7.6142226696 +17067 54.4258049525 -7.618827897 +17068 54.4276449115 -7.6237843299 +17069 54.4291777486 -7.6290393652 +17070 54.4303871803 -7.6345372078 +17071 54.4312603575 -7.6402194661 +17072 54.4317880028 -7.6460257756 +17073 54.4319645097 -7.6518944444 +17074 54.4338694444 -7.7130888889 +17075 54.4209643056 -7.694273 +17076 54.4231026591 -7.6906578306 +17077 54.4250421238 -7.6867264144 +17078 54.4267668889 -7.6825108056 +17079 54.4396833333 -7.7013388889 +17080 54.4338694444 -7.7130888889 +17081 54.3644027778 -7.5918305556 +17082 54.3765048056 -7.6093981667 +17083 54.3743600838 -7.61299728 +17084 54.3724133666 -7.6169125119 +17085 54.3706804722 -7.621112 +17086 54.3585888889 -7.6035555556 +17087 54.3644027778 -7.5918305556 +17088 54.6990927064 -6.2158333333 +17089 54.6989150989 -6.2224594592 +17090 54.698383796 -6.229028881 +17091 54.6975033443 -6.2354853842 +17092 54.6962812779 -6.2417737294 +17093 54.6947280529 -6.2478401287 +17094 54.6928569577 -6.2536327092 +17095 54.6906839982 -6.2591019599 +17096 54.6882277598 -6.2642011568 +17097 54.6855092472 -6.2688867638 +17098 54.6825517036 -6.2731188056 +17099 54.6793804105 -6.2768612078 +17100 54.6760224706 -6.2800821046 +17101 54.672506575 -6.2827541076 +17102 54.6688627568 -6.2848545372 +17103 54.6651221334 -6.2863656112 +17104 54.6613166408 -6.2872745925 +17105 54.6574787594 -6.2875738922 +17106 54.6536412373 -6.2872611287 +17107 54.6498368101 -6.286339142 +17108 54.6460979221 -6.2848159641 +17109 54.6424564499 -6.2827047442 +17110 54.6389434314 -6.2800236317 +17111 54.6355888016 -6.2767956168 +17112 54.6324211387 -6.27304833 +17113 54.6294674219 -6.2688138037 +17114 54.6267528025 -6.2641281966 +17115 54.6243003909 -6.2590314843 +17116 54.6221310617 -6.2535671181 +17117 54.6202632766 -6.2477816558 +17118 54.6187129286 -6.2417243659 +17119 54.6174932083 -6.2354468111 +17120 54.616614492 -6.2290024118 +17121 54.6160842545 -6.2224459954 +17122 54.6159070062 -6.2158333333 +17123 54.6160842545 -6.2092206713 +17124 54.616614492 -6.2026642549 +17125 54.6174932083 -6.1962198556 +17126 54.6187129286 -6.1899423008 +17127 54.6202632766 -6.1838850109 +17128 54.6221310617 -6.1780995485 +17129 54.6243003909 -6.1726351824 +17130 54.6267528025 -6.1675384701 +17131 54.6294674219 -6.162852863 +17132 54.6324211387 -6.1586183367 +17133 54.6355888016 -6.1548710499 +17134 54.6389434314 -6.151643035 +17135 54.6424564499 -6.1489619225 +17136 54.6460979221 -6.1468507026 +17137 54.6498368101 -6.1453275246 +17138 54.6536412373 -6.144405538 +17139 54.6574787594 -6.1440927744 +17140 54.6613166408 -6.1443920742 +17141 54.6651221334 -6.1453010555 +17142 54.6688627568 -6.1468121295 +17143 54.672506575 -6.148912559 +17144 54.6760224706 -6.1515845621 +17145 54.6793804105 -6.1548054589 +17146 54.6825517036 -6.1585478611 +17147 54.6855092472 -6.1627799028 +17148 54.6882277598 -6.1674655099 +17149 54.6906839982 -6.1725647068 +17150 54.6928569577 -6.1780339574 +17151 54.6947280529 -6.183826538 +17152 54.6962812779 -6.1898929372 +17153 54.6975033443 -6.1961812825 +17154 54.698383796 -6.2026377857 +17155 54.6989150989 -6.2092072075 +17156 54.6990927064 -6.2158333333 +17157 54.6292277778 -6.3021944444 +17158 54.6359791667 -6.2772079722 +17159 54.6386001004 -6.2797248099 +17160 54.6413194151 -6.2819096729 +17161 54.6441229722 -6.2837511667 +17162 54.6373777778 -6.3087138889 +17163 54.6292277778 -6.3021944444 +17164 54.6857388889 -6.1291305556 +17165 54.6789653889 -6.1543686389 +17166 54.6763409319 -6.1518605176 +17167 54.6736184898 -6.1496856953 +17168 54.67081225 -6.1478554167 +17169 54.6775916667 -6.1225944444 +17170 54.6857388889 -6.1291305556 +17171 54.6992365556 -6.2600159167 +17172 54.6919939444 -6.2559364167 +17173 54.693601312 -6.2514765225 +17174 54.6950153278 -6.2468253619 +17175 54.6962284167 -6.2420078889 +17176 54.7020187778 -6.2452674167 +17177 54.6992365556 -6.2600159167 +17178 54.6012328056 -6.18867225 +17179 54.6172657222 -6.1976555556 +17180 54.6166028186 -6.2027725007 +17181 54.6161585674 -6.2079591337 +17182 54.6159353333 -6.2131877778 +17183 54.5984505556 -6.2033843056 +17184 54.6012328056 -6.18867225 +17185 54.6513299617 -5.8725 +17186 54.6511534601 -5.8784002309 +17187 54.6506258306 -5.8842377659 +17188 54.6497526798 -5.8899505801 +17189 54.6485432848 -5.8954779834 +17190 54.6470104947 -5.9007612692 +17191 54.6451705926 -5.905744342 +17192 54.6430431218 -5.9103743152 +17193 54.6406506769 -5.9146020751 +17194 54.6380186624 -5.9183828029 +17195 54.6351750215 -5.9216764494 +17196 54.6321499383 -5.9244481591 +17197 54.6289755157 -5.9266686364 +17198 54.6256854341 -5.9283144534 +17199 54.6223145928 -5.9293682929 +17200 54.6188987388 -5.9298191266 +17201 54.6154740878 -5.9296623264 +17202 54.6120769396 -5.9288997065 +17203 54.6087432935 -5.9275394983 +17204 54.6055084673 -5.9255962562 +17205 54.6024067236 -5.9230906984 +17206 54.5994709081 -5.9200494818 +17207 54.5967321021 -5.9165049151 +17208 54.5942192958 -5.912494614 +17209 54.5919590816 -5.9080611001 +17210 54.5899753748 -5.90325135 +17211 54.588289162 -5.898116298 +17212 54.5869182798 -5.8927102986 +17213 54.5858772276 -5.8870905533 +17214 54.5851770156 -5.8813165087 +17215 54.5848250486 -5.8754492317 +17216 54.5848250486 -5.8695507683 +17217 54.5851770156 -5.8636834913 +17218 54.5858772276 -5.8579094467 +17219 54.5869182798 -5.8522897014 +17220 54.588289162 -5.846883702 +17221 54.5899753748 -5.84174865 +17222 54.5919590816 -5.8369388999 +17223 54.5942192958 -5.832505386 +17224 54.5967321021 -5.8284950849 +17225 54.5994709081 -5.8249505182 +17226 54.6024067236 -5.8219093016 +17227 54.6055084673 -5.8194037438 +17228 54.6087432935 -5.8174605017 +17229 54.6120769396 -5.8161002935 +17230 54.6154740878 -5.8153376736 +17231 54.6188987388 -5.8151808734 +17232 54.6223145928 -5.8156317071 +17233 54.6256854341 -5.8166855466 +17234 54.6289755157 -5.8183313636 +17235 54.6321499383 -5.8205518409 +17236 54.6351750215 -5.8233235506 +17237 54.6380186624 -5.8266171971 +17238 54.6406506769 -5.8303979249 +17239 54.6430431218 -5.8346256848 +17240 54.6451705926 -5.839255658 +17241 54.6470104947 -5.8442387308 +17242 54.6485432848 -5.8495220166 +17243 54.6497526798 -5.8550494199 +17244 54.6506258306 -5.8607622341 +17245 54.6511534601 -5.8665997691 +17246 54.6513299617 -5.8725 +17247 54.5725666667 -5.9174916667 +17248 54.5884211389 -5.8985663889 +17249 54.5899055038 -5.9030612095 +17250 54.5916190103 -5.9073076397 +17251 54.5935477222 -5.9112711389 +17252 54.5776916667 -5.9301944444 +17253 54.5725666667 -5.9174916667 +17254 54.6643027778 -5.8266055556 +17255 54.6477122778 -5.8464906111 +17256 54.6462309714 -5.8419875834 +17257 54.6445201629 -5.8377334708 +17258 54.6425938056 -5.8337629444 +17259 54.6591833333 -5.813875 +17260 54.6643027778 -5.8266055556 +17261 54.6143857216 -5.6919444444 +17262 54.6142092191 -5.69783933 +17263 54.613681587 -5.7036715766 +17264 54.6128084317 -5.7093792158 +17265 54.6115990305 -5.7149016127 +17266 54.6100662325 -5.720180114 +17267 54.6082263209 -5.725158675 +17268 54.6060988389 -5.7297844573 +17269 54.6037063812 -5.7340083916 +17270 54.6010743524 -5.7377856995 +17271 54.5982306958 -5.7410763683 +17272 54.5952055956 -5.7438455736 +17273 54.5920311548 -5.7460640464 +17274 54.5887410541 -5.7477083797 +17275 54.5853701927 -5.7487612717 +17276 54.581954318 -5.749211704 +17277 54.5785296459 -5.7490550522 +17278 54.5751324763 -5.7482931288 +17279 54.5717988089 -5.7469341571 +17280 54.5685639616 -5.7449926785 +17281 54.5654621975 -5.7424893921 +17282 54.5625263622 -5.7394509304 +17283 54.5597875376 -5.7359095728 +17284 54.5572747139 -5.7319029009 +17285 54.5550144839 -5.7274733979 +17286 54.5530307632 -5.7226679978 +17287 54.5513445384 -5.7175375889 +17288 54.5499736463 -5.7121364767 +17289 54.5489325867 -5.7065218111 +17290 54.5482323696 -5.7007529851 +17291 54.5478804001 -5.6948910108 +17292 54.5478804001 -5.6889978781 +17293 54.5482323696 -5.6831359038 +17294 54.5489325867 -5.6773670778 +17295 54.5499736463 -5.6717524122 +17296 54.5513445384 -5.6663513 +17297 54.5530307632 -5.6612208911 +17298 54.5550144839 -5.656415491 +17299 54.5572747139 -5.6519859879 +17300 54.5597875376 -5.6479793161 +17301 54.5625263622 -5.6444379585 +17302 54.5654621975 -5.6413994968 +17303 54.5685639616 -5.6388962103 +17304 54.5717988089 -5.6369547318 +17305 54.5751324763 -5.6355957601 +17306 54.5785296459 -5.6348338367 +17307 54.581954318 -5.6346771849 +17308 54.5853701927 -5.6351276172 +17309 54.5887410541 -5.6361805092 +17310 54.5920311548 -5.6378248425 +17311 54.5952055956 -5.6400433153 +17312 54.5982306958 -5.6428125206 +17313 54.6010743524 -5.6461031894 +17314 54.6037063812 -5.6498804973 +17315 54.6060988389 -5.6541044316 +17316 54.6082263209 -5.6587302139 +17317 54.6100662325 -5.6637087749 +17318 54.6115990305 -5.6689872762 +17319 54.6128084317 -5.6745096731 +17320 54.613681587 -5.6802173123 +17321 54.6142092191 -5.6860495589 +17322 54.6143857216 -5.6919444444 +17323 54.5372 -5.7285722222 +17324 54.5505698333 -5.7146738611 +17325 54.5518842841 -5.719318224 +17326 54.5534366053 -5.7237401423 +17327 54.5552141667 -5.7279036667 +17328 54.54185 -5.7417916667 +17329 54.5372 -5.7285722222 +17330 54.6242111111 -5.6560305556 +17331 54.6116395833 -5.6691476389 +17332 54.6103214286 -5.6644993349 +17333 54.6087652411 -5.660075022 +17334 54.6069837222 -5.6559107778 +17335 54.6195611111 -5.6427833333 +17336 54.6242111111 -5.6560305556 +17337 54.5655638889 -5.7707888889 +17338 54.5690223611 -5.7453074167 +17339 54.5718659434 -5.7469677702 +17340 54.5747849007 -5.7481803273 +17341 54.5777554722 -5.7489351389 +17342 54.5743138889 -5.7742916667 +17343 54.5655638889 -5.7707888889 +17344 54.5958166667 -5.6151472222 +17345 54.5927102222 -5.6382448611 +17346 54.5898510472 -5.6366648302 +17347 54.5869207834 -5.6355352653 +17348 54.5839433056 -5.6348652778 +17349 54.5870666667 -5.6116416667 +17350 54.5958166667 -5.6151472222 +17351 54.6211611111 -5.7383444444 +17352 54.6082122222 -5.7251928056 +17353 54.6098446568 -5.7208435871 +17354 54.6112424062 -5.7162579728 +17355 54.6123940278 -5.7114734444 +17356 54.6257194444 -5.7250027778 +17357 54.6211611111 -5.7383444444 +17358 54.5446027778 -5.6428055556 +17359 54.556013 -5.6543445833 +17360 54.5541442047 -5.6583959388 +17361 54.5524954264 -5.662720605 +17362 54.5510800833 -5.6672833056 +17363 54.5400444444 -5.6561194444 +17364 54.5446027778 -5.6428055556 +17365 54.1643771067 -3.2632277778 +17366 54.1642005933 -3.2690585169 +17367 54.1636729286 -3.2748273013 +17368 54.1627997191 -3.280472839 +17369 54.1615902424 -3.285935157 +17370 54.1600573477 -3.291156242 +17371 54.1582173188 -3.2960806603 +17372 54.1560896996 -3.3006561493 +17373 54.1536970853 -3.3048341738 +17374 54.1510648816 -3.3085704421 +17375 54.1482210329 -3.3118253756 +17376 54.1451957247 -3.3145645274 +17377 54.1420210617 -3.3167589447 +17378 54.1387307264 -3.3183854724 +17379 54.1353596202 -3.319426994 +17380 54.1319434927 -3.3198726078 +17381 54.1285185624 -3.3197177365 +17382 54.125121132 -3.3189641693 +17383 54.1217872042 -3.3176200374 +17384 54.1185520999 -3.3156997208 +17385 54.1154500854 -3.3132236912 +17386 54.1125140096 -3.3102182896 +17387 54.1097749575 -3.306715443 +17388 54.1072619224 -3.3027523237 +17389 54.1050015 -3.2983709527 +17390 54.1030176089 -3.2936177545 +17391 54.1013312379 -3.2885430655 +17392 54.0999602261 -3.2832006024 +17393 54.0989190751 -3.2776468964 +17394 54.0982187963 -3.2719406978 +17395 54.0978667957 -3.2661423583 +17396 54.0978667957 -3.2603131973 +17397 54.0982187963 -3.2545148578 +17398 54.0989190751 -3.2488086591 +17399 54.0999602261 -3.2432549531 +17400 54.1013312379 -3.2379124901 +17401 54.1030176089 -3.2328378011 +17402 54.1050015 -3.2280846029 +17403 54.1072619224 -3.2237032319 +17404 54.1097749575 -3.2197401125 +17405 54.1125140096 -3.216237266 +17406 54.1154500854 -3.2132318643 +17407 54.1185520999 -3.2107558347 +17408 54.1217872042 -3.2088355182 +17409 54.125121132 -3.2074913862 +17410 54.1285185624 -3.2067378191 +17411 54.1319434927 -3.2065829477 +17412 54.1353596202 -3.2070285615 +17413 54.1387307264 -3.2080700832 +17414 54.1420210617 -3.2096966109 +17415 54.1451957247 -3.2118910282 +17416 54.1482210329 -3.21463018 +17417 54.1510648816 -3.2178851135 +17418 54.1536970853 -3.2216213818 +17419 54.1560896996 -3.2257994062 +17420 54.1582173188 -3.2303748952 +17421 54.1600573477 -3.2352993136 +17422 54.1615902424 -3.2405203986 +17423 54.1627997191 -3.2459827166 +17424 54.1636729286 -3.2516282543 +17425 54.1642005933 -3.2573970386 +17426 54.1643771067 -3.2632277778 +17427 54.1756527778 -3.295125 +17428 54.1607845278 -3.2888458333 +17429 54.1620244874 -3.2841622035 +17430 54.1630103456 -3.2793062909 +17431 54.163734 -3.2743180556 +17432 54.1778111111 -3.2802583333 +17433 54.1756527778 -3.295125 +17434 54.0817777778 -3.2398166667 +17435 54.0991938333 -3.2471365833 +17436 54.0984692599 -3.25211691 +17437 54.0980124281 -3.2571882587 +17438 54.0978270833 -3.2623090833 +17439 54.0796194444 -3.25465 +17440 54.0817777778 -3.2398166667 +17441 54.3340952335 -1.5352777778 +17442 54.3339176176 -1.5418450861 +17443 54.3333862896 -1.548356196 +17444 54.3325057962 -1.5547553941 +17445 54.3312836713 -1.5609879334 +17446 54.3297303713 -1.567000505 +17447 54.3278591848 -1.572741698 +17448 54.3256861177 -1.5781624417 +17449 54.3232297559 -1.5832164274 +17450 54.3205111044 -1.5878605055 +17451 54.3175534068 -1.5920550547 +17452 54.3143819454 -1.5957643201 +17453 54.3110238238 -1.5989567169 +17454 54.3075077339 -1.6016050982 +17455 54.30386371 -1.6036869829 +17456 54.300122871 -1.6051847444 +17457 54.2963171542 -1.6060857555 +17458 54.292479042 -1.6063824916 +17459 54.2886412841 -1.6060725893 +17460 54.2848366185 -1.6051588604 +17461 54.2810974915 -1.6036492625 +17462 54.2774557822 -1.6015568259 +17463 54.2739425307 -1.5988995367 +17464 54.2705876747 -1.595700179 +17465 54.2674197949 -1.5919861371 +17466 54.2644658728 -1.5877891582 +17467 54.2617510621 -1.5831450801 +17468 54.2592984758 -1.578093524 +17469 54.2571289903 -1.5726775569 +17470 54.2552610693 -1.5669433247 +17471 54.2537106078 -1.5609396611 +17472 54.2524907976 -1.5547176737 +17473 54.2516120162 -1.5483303119 +17474 54.2510817393 -1.5418319199 +17475 54.2509044778 -1.5352777778 +17476 54.2510817393 -1.5287236356 +17477 54.2516120162 -1.5222252436 +17478 54.2524907976 -1.5158378819 +17479 54.2537106078 -1.5096158945 +17480 54.2552610693 -1.5036122309 +17481 54.2571289903 -1.4978779987 +17482 54.2592984758 -1.4924620315 +17483 54.2617510621 -1.4874104755 +17484 54.2644658728 -1.4827663974 +17485 54.2674197949 -1.4785694185 +17486 54.2705876747 -1.4748553766 +17487 54.2739425307 -1.4716560189 +17488 54.2774557822 -1.4689987296 +17489 54.2810974915 -1.466906293 +17490 54.2848366185 -1.4653966952 +17491 54.2886412841 -1.4644829663 +17492 54.292479042 -1.4641730639 +17493 54.2963171542 -1.4644698001 +17494 54.300122871 -1.4653708112 +17495 54.30386371 -1.4668685726 +17496 54.3075077339 -1.4689504574 +17497 54.3110238238 -1.4715988386 +17498 54.3143819454 -1.4747912355 +17499 54.3175534068 -1.4785005008 +17500 54.3205111044 -1.4826950501 +17501 54.3232297559 -1.4873391281 +17502 54.3256861177 -1.4923931138 +17503 54.3278591848 -1.4978138575 +17504 54.3297303713 -1.5035550505 +17505 54.3312836713 -1.5095676221 +17506 54.3325057962 -1.5158001614 +17507 54.3333862896 -1.5221993595 +17508 54.3339176176 -1.5287104694 +17509 54.3340952335 -1.5352777778 +17510 54.3410333333 -1.5811833333 +17511 54.3283361944 -1.5713919444 +17512 54.3297655331 -1.5668795474 +17513 54.3310008906 -1.5622023345 +17514 54.3320358333 -1.5573846944 +17515 54.3447194444 -1.5671611111 +17516 54.3410333333 -1.5811833333 +17517 54.2440083333 -1.4897166667 +17518 54.2566009444 -1.4993772778 +17519 54.2551807244 -1.5038895877 +17520 54.2539544356 -1.5085646991 +17521 54.2529284167 -1.5133783333 +17522 54.2403222222 -1.5037027778 +17523 54.2440083333 -1.4897166667 +17524 54.2546920278 -1.5696216944 +17525 54.2557684444 -1.5686279167 +17526 54.2572780563 -1.5730861296 +17527 54.2589728589 -1.5773459603 +17528 54.26084375 -1.58138525 +17529 54.2589676944 -1.5831166667 +17530 54.2546920278 -1.5696216944 +17531 54.3442184167 -1.5042563056 +17532 54.3324053056 -1.5152062778 +17533 54.3314499726 -1.5103125354 +17534 54.3302895303 -1.505550483 +17535 54.3289303333 -1.5009450833 +17536 54.3399428056 -1.4907334444 +17537 54.3442184167 -1.5042563056 +17538 54.5507603988 -1.4294444444 +17539 54.5505827878 -1.436046508 +17540 54.5500514747 -1.4425920743 +17541 54.5491710062 -1.449025134 +17542 54.547948916 -1.4552906489 +17543 54.5463956606 -1.4613350273 +17544 54.5445245284 -1.4671065851 +17545 54.5423515254 -1.4725559916 +17546 54.539895237 -1.4776366926 +17547 54.5371766681 -1.4823053102 +17548 54.534219062 -1.4865220138 +17549 54.5310477007 -1.4902508599 +17550 54.5276896871 -1.4934600974 +17551 54.5241737127 -1.4961224369 +17552 54.520529811 -1.4982152799 +17553 54.5167891002 -1.4997209079 +17554 54.5129835166 -1.5006266288 +17555 54.5091455415 -1.5009248799 +17556 54.5053079237 -1.500613287 +17557 54.5015033997 -1.4996946787 +17558 54.4977644147 -1.4981770565 +17559 54.4941228462 -1.4960735209 +17560 54.4906097331 -1.4934021546 +17561 54.4872550114 -1.4901858634 +17562 54.4840872604 -1.4864521771 +17563 54.4811334602 -1.4822330114 +17564 54.4784187631 -1.4775643938 +17565 54.4759662806 -1.4724861548 +17566 54.4737968879 -1.4670415886 +17567 54.4719290476 -1.4612770844 +17568 54.4703786535 -1.4552417328 +17569 54.4691588966 -1.4489869105 +17570 54.4682801539 -1.442565845 +17571 54.4677499004 -1.4360331662 +17572 54.4675726466 -1.4294444444 +17573 54.4677499004 -1.4228557227 +17574 54.4682801539 -1.4163230438 +17575 54.4691588966 -1.4099019784 +17576 54.4703786535 -1.4036471561 +17577 54.4719290476 -1.3976118045 +17578 54.4737968879 -1.3918473003 +17579 54.4759662806 -1.3864027341 +17580 54.4784187631 -1.3813244951 +17581 54.4811334602 -1.3766558775 +17582 54.4840872604 -1.3724367118 +17583 54.4872550114 -1.3687030255 +17584 54.4906097331 -1.3654867343 +17585 54.4941228462 -1.362815368 +17586 54.4977644147 -1.3607118324 +17587 54.5015033997 -1.3591942102 +17588 54.5053079237 -1.3582756019 +17589 54.5091455415 -1.357964009 +17590 54.5129835166 -1.3582622601 +17591 54.5167891002 -1.359167981 +17592 54.520529811 -1.360673609 +17593 54.5241737127 -1.362766452 +17594 54.5276896871 -1.3654287915 +17595 54.5310477007 -1.368638029 +17596 54.534219062 -1.3723668751 +17597 54.5371766681 -1.3765835787 +17598 54.539895237 -1.3812521963 +17599 54.5423515254 -1.3863328973 +17600 54.5445245284 -1.3917823038 +17601 54.5463956606 -1.3975538616 +17602 54.547948916 -1.40359824 +17603 54.5491710062 -1.4098637549 +17604 54.5500514747 -1.4162968146 +17605 54.5505827878 -1.4228423809 +17606 54.5507603988 -1.4294444444 +17607 54.468525 -1.4940166667 +17608 54.4778849722 -1.4765378333 +17609 54.4799412982 -1.4802882836 +17610 54.4821495716 -1.4837748599 +17611 54.4844983333 -1.4869794167 +17612 54.4751444444 -1.5044444444 +17613 54.468525 -1.4940166667 +17614 54.5498027778 -1.3646916667 +17615 54.5404305 -1.3822803611 +17616 54.5383711288 -1.3785290961 +17617 54.5361598086 -1.3750432165 +17618 54.5338080556 -1.3718408611 +17619 54.5431861111 -1.3542388889 +17620 54.5498027778 -1.3646916667 +17621 54.2389044702 -1.3816277778 +17622 54.2387279586 -1.3874690187 +17623 54.2382002993 -1.3932481928 +17624 54.2373270988 -1.3989038975 +17625 54.2361176346 -1.4043760513 +17626 54.2345847561 -1.4096065363 +17627 54.2327447467 -1.4145398186 +17628 54.2306171503 -1.4191235415 +17629 54.2282245621 -1.4233090821 +17630 54.2255923874 -1.4270520693 +17631 54.2227485706 -1.4303128533 +17632 54.2197232969 -1.4330569254 +17633 54.2165486709 -1.4352552811 +17634 54.2132583746 -1.4368847239 +17635 54.209887309 -1.4379281072 +17636 54.2064712235 -1.4383745099 +17637 54.203046336 -1.4382193472 +17638 54.1996489489 -1.437464412 +17639 54.1963150643 -1.4361178506 +17640 54.1930800027 -1.4341940696 +17641 54.1899780297 -1.4317135777 +17642 54.1870419937 -1.4287027635 +17643 54.1843029793 -1.4251936121 +17644 54.1817899792 -1.4212233625 +17645 54.1795295888 -1.4168341115 +17646 54.1775457259 -1.4120723669 +17647 54.1758593791 -1.4069885556 +17648 54.1744883872 -1.4016364907 +17649 54.1734472513 -1.3960728045 +17650 54.1727469828 -1.3903563526 +17651 54.1723949873 -1.3845475949 +17652 54.1723949873 -1.3787079606 +17653 54.1727469828 -1.372899203 +17654 54.1734472513 -1.3671827511 +17655 54.1744883872 -1.3616190649 +17656 54.1758593791 -1.356267 +17657 54.1775457259 -1.3511831886 +17658 54.1795295888 -1.3464214441 +17659 54.1817899792 -1.342032193 +17660 54.1843029793 -1.3380619434 +17661 54.1870419937 -1.334552792 +17662 54.1899780297 -1.3315419779 +17663 54.1930800027 -1.329061486 +17664 54.1963150643 -1.3271377049 +17665 54.1996489489 -1.3257911435 +17666 54.203046336 -1.3250362084 +17667 54.2064712235 -1.3248810456 +17668 54.209887309 -1.3253274484 +17669 54.2132583746 -1.3263708316 +17670 54.2165486709 -1.3280002745 +17671 54.2197232969 -1.3301986301 +17672 54.2227485706 -1.3329427022 +17673 54.2255923874 -1.3362034863 +17674 54.2282245621 -1.3399464734 +17675 54.2306171503 -1.3441320141 +17676 54.2327447467 -1.3487157369 +17677 54.2345847561 -1.3536490193 +17678 54.2361176346 -1.3588795043 +17679 54.2373270988 -1.3643516581 +17680 54.2382002993 -1.3700073628 +17681 54.2387279586 -1.3757865369 +17682 54.2389044702 -1.3816277778 +17683 54.1578682778 -1.40583975 +17684 54.1733367778 -1.3953372778 +17685 54.1741926445 -1.4002433356 +17686 54.1753043042 -1.4049981522 +17687 54.1766627222 -1.4095630833 +17688 54.1611958056 -1.4200591667 +17689 54.1578682778 -1.40583975 +17690 54.2566158889 -1.3551701389 +17691 54.2379189722 -1.3679102222 +17692 54.2370624949 -1.3629969339 +17693 54.2359498656 -1.3582356996 +17694 54.2345901667 -1.3536653611 +17695 54.2532884167 -1.3409179167 +17696 54.2566158889 -1.3551701389 +17697 54.2318486944 -1.4554805 +17698 54.2216514722 -1.4313874444 +17699 54.2242160026 -1.428721035 +17700 54.2266291543 -1.4256705754 +17701 54.22887125 -1.4222608889 +17702 54.2391268611 -1.4464896111 +17703 54.2318486944 -1.4554805 +17704 54.1814746111 -1.3105919444 +17705 54.1902709444 -1.3312787778 +17706 54.1876725655 -1.3338459199 +17707 54.185220428 -1.3368016981 +17708 54.1829344722 -1.340122 +17709 54.1741963889 -1.3195703333 +17710 54.1814746111 -1.3105919444 +17711 54.1851534167 -1.4628026944 +17712 54.1900875 -1.4318126944 +17713 54.1928130821 -1.4340062649 +17714 54.1956438446 -1.4357705656 +17715 54.1985565833 -1.4370910556 +17716 54.1938257778 -1.4668027778 +17717 54.1851534167 -1.4628026944 +17718 54.2197288889 -1.3034665833 +17719 54.215912 -1.3276355556 +17720 54.2130061059 -1.3262713683 +17721 54.2100397783 -1.3253615157 +17722 54.2070373611 -1.3249133611 +17723 54.2110565833 -1.299464 +17724 54.2197288889 -1.3034665833 +17725 54.1282577424 -4.6233333333 +17726 54.1280817561 -4.6300934172 +17727 54.1275551791 -4.6368004237 +17728 54.1266821455 -4.6434016959 +17729 54.1254695096 -4.6498454151 +17730 54.1239267908 -4.6560810113 +17731 54.1220660988 -4.6620595627 +17732 54.1199020374 -4.667734183 +17733 54.117451589 -4.6730603909 +17734 54.1147339801 -4.6779964608 +17735 54.1117705296 -4.6825037501 +17736 54.1085844801 -4.6865470027 +17737 54.1052008146 -4.6900946234 +17738 54.1016460595 -4.6931189245 +17739 54.0979480755 -4.6955963394 +17740 54.0941358383 -4.6975076042 +17741 54.0902392109 -4.6988379044 +17742 54.0862887089 -4.6995769864 +17743 54.0823152611 -4.6997192325 +17744 54.0783499674 -4.6992637003 +17745 54.0744238547 -4.6982141239 +17746 54.0705676349 -4.6965788803 +17747 54.0668114647 -4.694370918 +17748 54.0631847104 -4.6916076513 +17749 54.0597157192 -4.6883108199 +17750 54.0564315982 -4.6845063152 +17751 54.0533580037 -4.6802239747 +17752 54.050518942 -4.675497347 +17753 54.0479365828 -4.6703634275 +17754 54.0456310874 -4.6648623697 +17755 54.0436204524 -4.6590371708 +17756 54.0419203703 -4.6529333379 +17757 54.0405441082 -4.6465985335 +17758 54.0395024049 -4.6400822067 +17759 54.0388033878 -4.6334352097 +17760 54.0384525106 -4.6267094045 +17761 54.0384525106 -4.6199572621 +17762 54.0388033878 -4.613231457 +17763 54.0395024049 -4.60658446 +17764 54.0405441082 -4.6000681332 +17765 54.0419203703 -4.5937333288 +17766 54.0436204524 -4.5876294958 +17767 54.0456310874 -4.581804297 +17768 54.0479365828 -4.5763032391 +17769 54.050518942 -4.5711693197 +17770 54.0533580037 -4.5664426919 +17771 54.0564315982 -4.5621603515 +17772 54.0597157192 -4.5583558468 +17773 54.0631847104 -4.5550590154 +17774 54.0668114647 -4.5522957487 +17775 54.0705676349 -4.5500877864 +17776 54.0744238547 -4.5484525427 +17777 54.0783499674 -4.5474029664 +17778 54.0823152611 -4.5469474342 +17779 54.0862887089 -4.5470896803 +17780 54.0902392109 -4.5478287623 +17781 54.0941358383 -4.5491590625 +17782 54.0979480755 -4.5510703273 +17783 54.1016460595 -4.5535477422 +17784 54.1052008146 -4.5565720433 +17785 54.1085844801 -4.560119664 +17786 54.1117705296 -4.5641629166 +17787 54.1147339801 -4.5686702059 +17788 54.117451589 -4.5736062758 +17789 54.1199020374 -4.5789324837 +17790 54.1220660988 -4.584607104 +17791 54.1239267908 -4.5905856554 +17792 54.1254695096 -4.5968212515 +17793 54.1266821455 -4.6032649708 +17794 54.1275551791 -4.609866243 +17795 54.1280817561 -4.6165732494 +17796 54.1282577424 -4.6233333333 +17797 54.3567583333 -4.5316583333 +17798 54.3548138889 -4.5337277778 +17799 54.3545555556 -4.5336166667 +17800 54.353625 -4.5313527778 +17801 54.3537555556 -4.5287194444 +17802 54.3547611111 -4.5241055556 +17803 54.3588777778 -4.5280277778 +17804 54.3592833333 -4.5287472222 +17805 54.3580611111 -4.5304888889 +17806 54.3577472222 -4.5308222222 +17807 54.3567583333 -4.5316583333 +17808 54.5484861111 -1.9334416667 +17809 54.5456166667 -1.9503194444 +17810 54.5391583333 -1.9500527778 +17811 54.5372027778 -1.9359555556 +17812 54.5393777778 -1.9281472222 +17813 54.5484861111 -1.9334416667 +17814 54.7781138889 -1.5670861111 +17815 54.7768805556 -1.5776388889 +17816 54.7692666667 -1.5746444444 +17817 54.7673194444 -1.5645666667 +17818 54.7706861111 -1.5601888889 +17819 54.7763472222 -1.5609722222 +17820 54.7781138889 -1.5670861111 +17821 54.8109194444 -1.5424833333 +17822 54.8088 -1.5641277778 +17823 54.8027777778 -1.564175 +17824 54.7981777778 -1.5547861111 +17825 54.8001333333 -1.5392111111 +17826 54.8109194444 -1.5424833333 +17827 54.5833138889 -1.2967611111 +17828 54.5800361111 -1.302475 +17829 54.5763805556 -1.3024944444 +17830 54.5729222222 -1.2966055556 +17831 54.5729055556 -1.2882555556 +17832 54.5759472222 -1.2827388889 +17833 54.58325 -1.2874805556 +17834 54.5833138889 -1.2967611111 +17835 54.0601888889 -2.7730277778 +17836 54.058 -2.7780666667 +17837 54.0525166667 -2.7792722222 +17838 54.0490194444 -2.7747222222 +17839 54.0486583333 -2.7687166667 +17840 54.0510416667 -2.7634277778 +17841 54.0569194444 -2.7621972222 +17842 54.0595777778 -2.7657555556 +17843 54.0601888889 -2.7730277778 +17844 55.084367829 -7.1619444444 +17845 55.0841902302 -7.16863411 +17846 55.0836589535 -7.1752665251 +17847 55.0827785455 -7.1817849341 +17848 55.08155654 -7.1881335654 +17849 55.0800033933 -7.1942581135 +17850 55.0781323936 -7.2001062067 +17851 55.0759595465 -7.205627858 +17852 55.0735034372 -7.2107758951 +17853 55.07078507 -7.2155063643 +17854 55.0678276874 -7.2197789075 +17855 55.0646565705 -7.2235571058 +17856 55.0612988211 -7.2268087892 +17857 55.0577831292 -7.2295063091 +17858 55.0541395266 -7.2316267707 +17859 55.0503991296 -7.2331522246 +17860 55.0465938723 -7.2340698146 +17861 55.0427562335 -7.2343718823 +17862 55.038918959 -7.2340560266 +17863 55.0351147825 -7.2331251182 +17864 55.0313761459 -7.2315872689 +17865 55.0277349233 -7.229455757 +17866 55.0242221499 -7.2267489084 +17867 55.0208677583 -7.2234899355 +17868 55.0177003241 -7.2197067351 +17869 55.0147468236 -7.2154316474 +17870 55.0120324057 -7.2107011782 +17871 55.0095801785 -7.2055556855 +17872 55.0074110141 -7.2000390363 +17873 55.0055433721 -7.1941982326 +17874 55.003993144 -7.1880830132 +17875 55.0027735185 -7.1817454321 +17876 55.0018948709 -7.1752394186 +17877 55.001364675 -7.1686203219 +17878 55.0011874405 -7.1619444444 +17879 55.001364675 -7.1552685669 +17880 55.0018948709 -7.1486494703 +17881 55.0027735185 -7.1421434567 +17882 55.003993144 -7.1358058756 +17883 55.0055433721 -7.1296906563 +17884 55.0074110141 -7.1238498526 +17885 55.0095801785 -7.1183332034 +17886 55.0120324057 -7.1131877107 +17887 55.0147468236 -7.1084572414 +17888 55.0177003241 -7.1041821538 +17889 55.0208677583 -7.1003989534 +17890 55.0242221499 -7.0971399805 +17891 55.0277349233 -7.0944331319 +17892 55.0313761459 -7.09230162 +17893 55.0351147825 -7.0907637707 +17894 55.038918959 -7.0898328623 +17895 55.0427562335 -7.0895170066 +17896 55.0465938723 -7.0898190743 +17897 55.0503991296 -7.0907366643 +17898 55.0541395266 -7.0922621182 +17899 55.0577831292 -7.0943825798 +17900 55.0612988211 -7.0970800997 +17901 55.0646565705 -7.1003317831 +17902 55.0678276874 -7.1041099814 +17903 55.07078507 -7.1083825246 +17904 55.0735034372 -7.1131129938 +17905 55.0759595465 -7.1182610309 +17906 55.0781323936 -7.1237826822 +17907 55.0800033933 -7.1296307754 +17908 55.08155654 -7.1357553235 +17909 55.0827785455 -7.1421039548 +17910 55.0836589535 -7.1486223637 +17911 55.0841902302 -7.1552547789 +17912 55.084367829 -7.1619444444 +17913 55.0229694444 -7.2479777778 +17914 55.02637775 -7.2284896389 +17915 55.029174606 -7.2303766768 +17916 55.0320422966 -7.2319081121 +17917 55.0349659167 -7.2330759167 +17918 55.0315666667 -7.2525111111 +17919 55.0229694444 -7.2479777778 +17920 55.0625416667 -7.0746277778 +17921 55.0589717778 -7.0952194167 +17922 55.056167767 -7.0933618418 +17923 55.0532941684 -7.091861437 +17924 55.0503659444 -7.0907259444 +17925 55.0539444444 -7.0700833333 +17926 55.0625416667 -7.0746277778 +17927 55.7166018889 -6.2597222222 +17928 55.7164254124 -6.2657819823 +17929 55.7158978586 -6.271777345 +17930 55.7150248334 -6.2776446024 +17931 55.7138156138 -6.2833214183 +17932 55.712283048 -6.2887474943 +17933 55.7104434183 -6.2938652149 +17934 55.7083162666 -6.2986202621 +17935 55.705924186 -6.3029621938 +17936 55.7032925788 -6.3068449806 +17937 55.7004493856 -6.3102274936 +17938 55.6974247876 -6.313073939 +17939 55.6942508839 -6.3153542352 +17940 55.6909613507 -6.3170443274 +17941 55.6875910823 -6.318126438 +17942 55.6841758205 -6.3185892489 +17943 55.6807517748 -6.3184280152 +17944 55.6773552385 -6.3176446087 +17945 55.674022204 -6.316247491 +17946 55.6707879818 -6.3142516173 +17947 55.6676868271 -6.3116782717 +17948 55.6647515777 -6.3085548363 +17949 55.6620133077 -6.3049144963 +17950 55.6595009996 -6.3007958855 +17951 55.6572412388 -6.2962426744 +17952 55.6552579343 -6.291303107 +17953 55.6535720664 -6.2860294903 +17954 55.6522014666 -6.2804776422 +17955 55.6511606303 -6.2747063031 +17956 55.650460564 -6.2687765182 +17957 55.6501086704 -6.2627509957 +17958 55.6501086704 -6.2566934487 +17959 55.650460564 -6.2506679263 +17960 55.6511606303 -6.2447381414 +17961 55.6522014666 -6.2389668023 +17962 55.6535720664 -6.2334149541 +17963 55.6552579343 -6.2281413375 +17964 55.6572412388 -6.22320177 +17965 55.6595009996 -6.2186485589 +17966 55.6620133077 -6.2145299481 +17967 55.6647515777 -6.2108896082 +17968 55.6676868271 -6.2077661728 +17969 55.6707879818 -6.2051928272 +17970 55.674022204 -6.2031969535 +17971 55.6773552385 -6.2017998358 +17972 55.6807517748 -6.2010164292 +17973 55.6841758205 -6.2008551956 +17974 55.6875910823 -6.2013180065 +17975 55.6909613507 -6.202400117 +17976 55.6942508839 -6.2040902092 +17977 55.6974247876 -6.2063705054 +17978 55.7004493856 -6.2092169508 +17979 55.7032925788 -6.2125994638 +17980 55.705924186 -6.2164822507 +17981 55.7083162666 -6.2208241824 +17982 55.7104434183 -6.2255792295 +17983 55.712283048 -6.2306969501 +17984 55.7138156138 -6.2361230262 +17985 55.7150248334 -6.241799842 +17986 55.7158978586 -6.2476670995 +17987 55.7164254124 -6.2536624622 +17988 55.7166018889 -6.2597222222 +17989 55.6632111111 -6.3310583333 +17990 55.6671968889 -6.3112065278 +17991 55.6698858046 -6.3135733497 +17992 55.6726843614 -6.3155017861 +17993 55.6755697778 -6.3169760278 +17994 55.6716777778 -6.3363611111 +17995 55.6632111111 -6.3310583333 +17996 55.7033861111 -6.1778694444 +17997 55.6976632222 -6.20656975 +17998 55.6948971441 -6.2045004609 +17999 55.6920369256 -6.2028814671 +18000 55.6891058889 -6.2017258611 +18001 55.6949222222 -6.1725583333 +18002 55.7033861111 -6.1778694444 +18003 55.7055111111 -6.3406861111 +18004 55.6964641944 -6.3138358611 +18005 55.6991669056 -6.3115212547 +18006 55.7017407062 -6.3087842929 +18007 55.7041646111 -6.3056472222 +18008 55.7132194444 -6.3325194444 +18009 55.7055111111 -6.3406861111 +18010 55.6612916667 -6.1788166667 +18011 55.6703383333 -6.2055239444 +18012 55.667630681 -6.2078192916 +18013 55.6650509551 -6.2105368535 +18014 55.6626201389 -6.2136544444 +18015 55.6535805556 -6.1869666667 +18016 55.6612916667 -6.1788166667 +18017 55.4708865645 -5.6881 +18018 55.4707100823 -5.6941220147 +18019 55.4701825112 -5.7000800346 +18020 55.4693094573 -5.7059107502 +18021 55.4681001977 -5.7115522144 +18022 55.4665675807 -5.7169445058 +18023 55.4647278888 -5.7220303684 +18024 55.4626006643 -5.7267558229 +18025 55.4602085004 -5.7310707415 +18026 55.4575768001 -5.7349293813 +18027 55.4547335046 -5.7382908687 +18028 55.4517087954 -5.7411196321 +18029 55.448534773 -5.7433857756 +18030 55.4452451142 -5.7450653929 +18031 55.4418747144 -5.7461408152 +18032 55.4384593168 -5.746600793 +18033 55.4350351322 -5.746440609 +18034 55.4316384554 -5.7456621213 +18035 55.4283052805 -5.744273737 +18036 55.4250709195 -5.7422903165 +18037 55.4219696294 -5.73973301 +18038 55.4190342499 -5.7366290279 +18039 55.4162958566 -5.7330113481 +18040 55.4137834338 -5.7289183635 +18041 55.4115235687 -5.7243934726 +18042 55.4095401715 -5.7194846198 +18043 55.4078542242 -5.7142437872 +18044 55.4064835594 -5.7087264464 +18045 55.4054426733 -5.7029909739 +18046 55.4047425735 -5.6970980365 +18047 55.404390663 -5.6911099543 +18048 55.404390663 -5.6850900457 +18049 55.4047425735 -5.6791019635 +18050 55.4054426733 -5.6732090261 +18051 55.4064835594 -5.6674735536 +18052 55.4078542242 -5.6619562128 +18053 55.4095401715 -5.6567153802 +18054 55.4115235687 -5.6518065274 +18055 55.4137834338 -5.6472816365 +18056 55.4162958566 -5.6431886519 +18057 55.4190342499 -5.6395709721 +18058 55.4219696294 -5.63646699 +18059 55.4250709195 -5.6339096835 +18060 55.4283052805 -5.631926263 +18061 55.4316384554 -5.6305378787 +18062 55.4350351322 -5.629759391 +18063 55.4384593168 -5.629599207 +18064 55.4418747144 -5.6300591848 +18065 55.4452451142 -5.6311346071 +18066 55.448534773 -5.6328142244 +18067 55.4517087954 -5.6350803679 +18068 55.4547335046 -5.6379091313 +18069 55.4575768001 -5.6412706187 +18070 55.4602085004 -5.6451292585 +18071 55.4626006643 -5.6494441771 +18072 55.4647278888 -5.6541696316 +18073 55.4665675807 -5.6592554942 +18074 55.4681001977 -5.6646477856 +18075 55.4693094573 -5.6702892498 +18076 55.4701825112 -5.6761199654 +18077 55.4707100823 -5.6820779853 +18078 55.4708865645 -5.6881 +18079 55.4461494167 -5.7688818889 +18080 55.4424185278 -5.74600975 +18081 55.4453669439 -5.7450145588 +18082 55.4482523464 -5.7435556738 +18083 55.4510512222 -5.7416448611 +18084 55.4547803611 -5.7645058056 +18085 55.4461494167 -5.7688818889 +18086 55.4263978889 -5.5912708611 +18087 55.4328010278 -5.6302008333 +18088 55.4298533037 -5.6312021234 +18089 55.4269688867 -5.6326664256 +18090 55.42417125 -5.63458175 +18091 55.4177668889 -5.5956437778 +18092 55.4263978889 -5.5912708611 +18093 55.5509785198 -4.5945805556 +18094 55.5508009314 -4.6013492444 +18095 55.550269686 -4.6080600036 +18096 55.5493893301 -4.6146554036 +18097 55.5481673976 -4.6210790116 +18098 55.5466143445 -4.6272758781 +18099 55.5447434589 -4.6331930109 +18100 55.5425707464 -4.6387798314 +18101 55.5401147917 -4.6439886091 +18102 55.5373965986 -4.6487748714 +18103 55.5344394092 -4.6530977841 +18104 55.5312685036 -4.6569204995 +18105 55.5279109828 -4.6602104698 +18106 55.5243955356 -4.6629397226 +18107 55.5207521923 -4.6650850957 +18108 55.5170120675 -4.6666284315 +18109 55.5132070933 -4.6675567258 +18110 55.5093697465 -4.6678622339 +18111 55.5055327706 -4.6675425307 +18112 55.5017288963 -4.6666005248 +18113 55.4979905628 -4.6650444277 +18114 55.4943496414 -4.6628876781 +18115 55.4908371641 -4.6601488213 +18116 55.4874830602 -4.6568513462 +18117 55.4843159021 -4.6530234809 +18118 55.4813626631 -4.6486979487 +18119 55.4786484888 -4.6439116863 +18120 55.4761964845 -4.6387055281 +18121 55.4740275195 -4.6331238575 +18122 55.4721600508 -4.6272142294 +18123 55.4706099677 -4.621026967 +18124 55.469390457 -4.6146147355 +18125 55.4685118925 -4.6080320968 +18126 55.4679817469 -4.6013350494 +18127 55.4678045293 -4.5945805556 +18128 55.4679817469 -4.5878260617 +18129 55.4685118925 -4.5811290143 +18130 55.469390457 -4.5745463757 +18131 55.4706099677 -4.5681341441 +18132 55.4721600508 -4.5619468817 +18133 55.4740275195 -4.5560372536 +18134 55.4761964845 -4.550455583 +18135 55.4786484888 -4.5452494248 +18136 55.4813626631 -4.5404631624 +18137 55.4843159021 -4.5361376302 +18138 55.4874830602 -4.5323097649 +18139 55.4908371641 -4.5290122898 +18140 55.4943496414 -4.526273433 +18141 55.4979905628 -4.5241166834 +18142 55.5017288963 -4.5225605863 +18143 55.5055327706 -4.5216185804 +18144 55.5093697465 -4.5212988772 +18145 55.5132070933 -4.5216043854 +18146 55.5170120675 -4.5225326796 +18147 55.5207521923 -4.5240760154 +18148 55.5243955356 -4.5262213885 +18149 55.5279109828 -4.5289506413 +18150 55.5312685036 -4.5322406116 +18151 55.5344394092 -4.536063327 +18152 55.5373965986 -4.5403862397 +18153 55.5401147917 -4.545172502 +18154 55.5425707464 -4.5503812797 +18155 55.5447434589 -4.5559681002 +18156 55.5466143445 -4.561885233 +18157 55.5481673976 -4.5680820995 +18158 55.5493893301 -4.5745057075 +18159 55.550269686 -4.5811011075 +18160 55.5508009314 -4.5878118667 +18161 55.5509785198 -4.5945805556 +18162 55.4454555556 -4.6119638889 +18163 55.4678045556 -4.5946817778 +18164 55.467927257 -4.6002036153 +18165 55.4682859911 -4.605693511 +18166 55.4688787222 -4.6111202778 +18167 55.4490722222 -4.6264277778 +18168 55.4454555556 -4.6119638889 +18169 55.5462972222 -4.551125 +18170 55.5436986389 -4.5531429722 +18171 55.5418268629 -4.548697861 +18172 55.539770143 -4.5445148706 +18173 55.5375402222 -4.5406178611 +18174 55.5426833333 -4.5366222222 +18175 55.5462972222 -4.551125 +18176 55.534725 -4.6832444444 +18177 55.5270424444 -4.6609490833 +18178 55.5297116791 -4.6585352738 +18179 55.5322752062 -4.655788149 +18180 55.5347196667 -4.6527219722 +18181 55.5423972222 -4.675 +18182 55.534725 -4.6832444444 +18183 55.4828555556 -4.5027611111 +18184 55.4917018333 -4.528274 +18185 55.4890358972 -4.5306940537 +18186 55.4864758646 -4.5334458761 +18187 55.4840350278 -4.5365151111 +18188 55.4751833333 -4.5109833333 +18189 55.4828555556 -4.5027611111 +18190 55.9133066058 -4.4336611111 +18191 55.9131290254 -4.4404927814 +18192 55.9125978039 -4.4472659805 +18193 55.911717488 -4.4539227421 +18194 55.9104956113 -4.4604061061 +18195 55.90894263 -4.4666606098 +18196 55.907071832 -4.4726327666 +18197 55.9048992227 -4.4782715259 +18198 55.9024433866 -4.4835287129 +18199 55.8997253273 -4.4883594411 +18200 55.8967682863 -4.4927224969 +18201 55.8935975433 -4.4965806909 +18202 55.8902401984 -4.4999011742 +18203 55.8867249395 -4.5026557162 +18204 55.883081796 -4.5048209421 +18205 55.8793418811 -4.5063785279 +18206 55.8755371254 -4.5073153518 +18207 55.8717000041 -4.5076236004 +18208 55.8678632586 -4.5073008292 +18209 55.8640596179 -4.5063499773 +18210 55.8603215189 -4.5047793358 +18211 55.8566808305 -4.502602471 +18212 55.8531685823 -4.4998381033 +18213 55.8498147012 -4.496509942 +18214 55.846647757 -4.4926464793 +18215 55.8436947207 -4.4882807436 +18216 55.8409807353 -4.4834500153 +18217 55.8385289038 -4.4781955083 +18218 55.8363600934 -4.4725620176 +18219 55.8344927591 -4.4665975388 +18220 55.8329427885 -4.4603528607 +18221 55.8317233669 -4.4538811356 +18222 55.8308448669 -4.4472374298 +18223 55.8303147604 -4.4404782588 +18224 55.8301375558 -4.4336611111 +18225 55.8303147604 -4.4268439634 +18226 55.8308448669 -4.4200847924 +18227 55.8317233669 -4.4134410866 +18228 55.8329427885 -4.4069693615 +18229 55.8344927591 -4.4007246835 +18230 55.8363600934 -4.3947602046 +18231 55.8385289038 -4.3891267139 +18232 55.8409807353 -4.3838722069 +18233 55.8436947207 -4.3790414787 +18234 55.846647757 -4.3746757429 +18235 55.8498147012 -4.3708122802 +18236 55.8531685823 -4.367484119 +18237 55.8566808305 -4.3647197512 +18238 55.8603215189 -4.3625428864 +18239 55.8640596179 -4.3609722449 +18240 55.8678632586 -4.360021393 +18241 55.8717000041 -4.3596986219 +18242 55.8755371254 -4.3600068705 +18243 55.8793418811 -4.3609436943 +18244 55.883081796 -4.3625012801 +18245 55.8867249395 -4.364666506 +18246 55.8902401984 -4.367421048 +18247 55.8935975433 -4.3707415313 +18248 55.8967682863 -4.3745997254 +18249 55.8997253273 -4.3789627812 +18250 55.9024433866 -4.3837935094 +18251 55.9048992227 -4.3890506963 +18252 55.907071832 -4.3946894557 +18253 55.90894263 -4.4006616124 +18254 55.9104956113 -4.4069161161 +18255 55.911717488 -4.4133994801 +18256 55.9125978039 -4.4200562418 +18257 55.9131290254 -4.4268294408 +18258 55.9133066058 -4.4336611111 +18259 55.8292444444 -4.5013388889 +18260 55.8399566111 -4.4813740556 +18261 55.8419728253 -4.4853205407 +18262 55.844143751 -4.4889988796 +18263 55.8464581111 -4.4923899444 +18264 55.8357527778 -4.5123388889 +18265 55.8292444444 -4.5013388889 +18266 55.9122694444 -4.3693777778 +18267 55.9034677222 -4.3858671944 +18268 55.9014481405 -4.3819197029 +18269 55.8992738431 -4.3782420207 +18270 55.8969561667 -4.3748532778 +18271 55.9057638889 -4.35835 +18272 55.9122694444 -4.3693777778 +18273 56.0079225256 -3.9754333333 +18274 56.0077460559 -3.9815386102 +18275 56.0072185223 -3.9875790042 +18276 56.0063455309 -3.9934903273 +18277 56.0051363583 -3.9992097732 +18278 56.0036038528 -4.0046765897 +18279 56.0017642963 -4.0098327274 +18280 55.9996372304 -4.0146234598 +18281 55.9972452479 -4.0189979659 +18282 55.9946137503 -4.0229098711 +18283 55.991770678 -4.026317738 +18284 55.9887462108 -4.0291855056 +18285 55.9855724473 -4.0314828677 +18286 55.9822830623 -4.0331855908 +18287 55.978912949 -4.0342757661 +18288 55.9754978476 -4.0347419927 +18289 55.9720739659 -4.0345794927 +18290 55.9686775956 -4.0337901541 +18291 55.9653447272 -4.0323825044 +18292 55.9621106691 -4.0303716132 +18293 55.9590096745 -4.0277789261 +18294 55.9560745792 -4.0246320321 +18295 55.953336455 -4.0209643667 +18296 55.9508242826 -4.0168148538 +18297 55.9485646454 -4.012227492 +18298 55.9465814505 -4.0072508868 +18299 55.9448956766 -4.0019377369 +18300 55.9435251539 -3.9963442776 +18301 55.9424843764 -3.9905296883 +18302 55.9417843499 -3.9845554704 +18303 55.9414324764 -3.9784848002 +18304 55.9414324764 -3.9723818665 +18305 55.9417843499 -3.9663111963 +18306 55.9424843764 -3.9603369783 +18307 55.9435251539 -3.9545223891 +18308 55.9448956766 -3.9489289298 +18309 55.9465814505 -3.9436157799 +18310 55.9485646454 -3.9386391747 +18311 55.9508242826 -3.9340518128 +18312 55.953336455 -3.9299023 +18313 55.9560745792 -3.9262346345 +18314 55.9590096745 -3.9230877405 +18315 55.9621106691 -3.9204950535 +18316 55.9653447272 -3.9184841622 +18317 55.9686775956 -3.9170765126 +18318 55.9720739659 -3.916287174 +18319 55.9754978476 -3.9161246739 +18320 55.978912949 -3.9165909006 +18321 55.9822830623 -3.9176810758 +18322 55.9855724473 -3.919383799 +18323 55.9887462108 -3.9216811611 +18324 55.991770678 -3.9245489286 +18325 55.9946137503 -3.9279567956 +18326 55.9972452479 -3.9318687007 +18327 55.9996372304 -3.9362432069 +18328 56.0017642963 -3.9410339393 +18329 56.0036038528 -3.946190077 +18330 56.0051363583 -3.9516568934 +18331 56.0063455309 -3.9573763394 +18332 56.0072185223 -3.9632876624 +18333 56.0077460559 -3.9693280564 +18334 56.0079225256 -3.9754333333 +18335 55.9557666667 -4.0556527778 +18336 55.9604704167 -4.0290868333 +18337 55.9632401287 -4.031149962 +18338 55.9661028542 -4.0327598646 +18339 55.9690353056 -4.0339033333 +18340 55.9643333333 -4.0604583333 +18341 55.9557666667 -4.0556527778 +18342 55.9934916667 -3.8951527778 +18343 55.9888194444 -3.9217423611 +18344 55.9860479238 -3.9196852867 +18345 55.9831837186 -3.9180825215 +18346 55.9802501667 -3.9169470278 +18347 55.984925 -3.8903416667 +18348 55.9934916667 -3.8951527778 +18349 55.9915838517 -3.3725 +18350 55.991406273 -3.3793454676 +18351 55.9908750567 -3.3861323453 +18352 55.9899947493 -3.3928025494 +18353 55.9887728846 -3.399299004 +18354 55.9872199186 -3.4055661343 +18355 55.9853491394 -3.411550345 +18356 55.9831765523 -3.4172004825 +18357 55.9807207417 -3.4224682743 +18358 55.9780027111 -3.4273087435 +18359 55.975045702 -3.4316805932 +18360 55.9718749939 -3.4355465594 +18361 55.9685176868 -3.438873727 +18362 55.9650024685 -3.4416338089 +18363 55.9613593679 -3.4438033837 +18364 55.9576194981 -3.445364091 +18365 55.9538147896 -3.4463027832 +18366 55.9499777168 -3.446611632 +18367 55.946141021 -3.4462881886 +18368 55.9423374306 -3.4453353986 +18369 55.9385993821 -3.4437615707 +18370 55.9349587439 -3.4415802993 +18371 55.9314465451 -3.4388103428 +18372 55.9280927121 -3.4354754592 +18373 55.9249258141 -3.4316041982 +18374 55.9219728214 -3.4272296552 +18375 55.9192588768 -3.422389186 +18376 55.9168070827 -3.4171240874 +18377 55.9146383056 -3.4114792447 +18378 55.9127710004 -3.40550275 +18379 55.9112210541 -3.3992454943 +18380 55.9100016517 -3.3927607363 +18381 55.9091231656 -3.3861036529 +18382 55.9085930675 -3.3793308729 +18383 55.9084158658 -3.3725 +18384 55.9085930675 -3.3656691271 +18385 55.9091231656 -3.3588963471 +18386 55.9100016517 -3.3522392637 +18387 55.9112210541 -3.3457545057 +18388 55.9127710004 -3.33949725 +18389 55.9146383056 -3.3335207553 +18390 55.9168070827 -3.3278759126 +18391 55.9192588768 -3.322610814 +18392 55.9219728214 -3.3177703448 +18393 55.9249258141 -3.3133958018 +18394 55.9280927121 -3.3095245408 +18395 55.9314465451 -3.3061896572 +18396 55.9349587439 -3.3034197007 +18397 55.9385993821 -3.3012384293 +18398 55.9423374306 -3.2996646014 +18399 55.946141021 -3.2987118114 +18400 55.9499777168 -3.298388368 +18401 55.9538147896 -3.2986972168 +18402 55.9576194981 -3.299635909 +18403 55.9613593679 -3.3011966163 +18404 55.9650024685 -3.3033661911 +18405 55.9685176868 -3.306126273 +18406 55.9718749939 -3.3094534406 +18407 55.975045702 -3.3133194068 +18408 55.9780027111 -3.3176912565 +18409 55.9807207417 -3.3225317257 +18410 55.9831765523 -3.3277995175 +18411 55.9853491394 -3.333449655 +18412 55.9872199186 -3.3394338657 +18413 55.9887728846 -3.345700996 +18414 55.9899947493 -3.3521974506 +18415 55.9908750567 -3.3588676547 +18416 55.991406273 -3.3656545324 +18417 55.9915838517 -3.3725 +18418 55.9179055556 -3.4515083333 +18419 55.9247520556 -3.4313687778 +18420 55.9271983849 -3.4344587671 +18421 55.9297633256 -3.4372270503 +18422 55.9324335556 -3.4396591944 +18423 55.9255944444 -3.459775 +18424 55.9179055556 -3.4515083333 +18425 55.9819416667 -3.2935388889 +18426 55.9751909167 -3.3135155278 +18427 55.9727397804 -3.3104327879 +18428 55.970170342 -3.3076735423 +18429 55.967496 -3.3052520833 +18430 55.9742527778 -3.2852555556 +18431 55.9819416667 -3.2935388889 +18432 55.0795123069 -1.6898111111 +18433 55.0793347079 -1.6964999664 +18434 55.0788034309 -1.7031315782 +18435 55.0779230223 -1.7096491977 +18436 55.0767010161 -1.7159970603 +18437 55.0751478684 -1.7221208669 +18438 55.0732768675 -1.7279682522 +18439 55.071104019 -1.7334892353 +18440 55.0686479081 -1.7386366495 +18441 55.065929539 -1.7433665467 +18442 55.0629721544 -1.7476385734 +18443 55.0598010353 -1.7514163152 +18444 55.0564432835 -1.754667606 +18445 55.0529275891 -1.7573648005 +18446 55.0492839838 -1.7594850068 +18447 55.0455435839 -1.7610102773 +18448 55.0417383236 -1.7619277575 +18449 55.0379006818 -1.7622297899 +18450 55.0340634042 -1.7619139737 +18451 55.0302592245 -1.760983179 +18452 55.0265205847 -1.7594455168 +18453 55.022879359 -1.7573142637 +18454 55.0193665826 -1.7546077433 +18455 55.016012188 -1.7513491651 +18456 55.0128447508 -1.7475664227 +18457 55.0098912476 -1.7432918523 +18458 55.0071768272 -1.7385619551 +18459 55.0047245977 -1.7334170845 +18460 55.0025554312 -1.727901102 +18461 55.0006877874 -1.7220610041 +18462 54.9991375578 -1.7159465234 +18463 54.9979179311 -1.7096097077 +18464 54.9970392826 -1.7031044799 +18465 54.9965090862 -1.6964861825 +18466 54.9963318516 -1.6898111111 +18467 54.9965090862 -1.6831360397 +18468 54.9970392826 -1.6765177423 +18469 54.9979179311 -1.6700125145 +18470 54.9991375578 -1.6636756989 +18471 55.0006877874 -1.6575612182 +18472 55.0025554312 -1.6517211202 +18473 55.0047245977 -1.6462051377 +18474 55.0071768272 -1.6410602671 +18475 55.0098912476 -1.6363303699 +18476 55.0128447508 -1.6320557995 +18477 55.016012188 -1.6282730571 +18478 55.0193665826 -1.6250144789 +18479 55.022879359 -1.6223079585 +18480 55.0265205847 -1.6201767054 +18481 55.0302592245 -1.6186390432 +18482 55.0340634042 -1.6177082486 +18483 55.0379006818 -1.6173924323 +18484 55.0417383236 -1.6176944647 +18485 55.0455435839 -1.6186119449 +18486 55.0492839838 -1.6201372155 +18487 55.0529275891 -1.6222574217 +18488 55.0564432835 -1.6249546162 +18489 55.0598010353 -1.628205907 +18490 55.0629721544 -1.6319836488 +18491 55.065929539 -1.6362556755 +18492 55.0686479081 -1.6409855727 +18493 55.071104019 -1.6461329869 +18494 55.0732768675 -1.6516539701 +18495 55.0751478684 -1.6575013554 +18496 55.0767010161 -1.6636251619 +18497 55.0779230223 -1.6699730245 +18498 55.0788034309 -1.676490644 +18499 55.0793347079 -1.6831222558 +18500 55.0795123069 -1.6898111111 +18501 55.0110388889 -1.7723027778 +18502 55.0164843056 -1.7518513611 +18503 55.0191080779 -1.7543812399 +18504 55.0218297539 -1.7565757289 +18505 55.0246351944 -1.7584233611 +18506 55.0191944444 -1.7788555556 +18507 55.0110388889 -1.7723027778 +18508 55.0646833333 -1.6074555556 +18509 55.0593275 -1.6277036667 +18510 55.0567007126 -1.6251793523 +18511 55.05397627 -1.622991767 +18512 55.0511683611 -1.62115225 +18513 55.0565277778 -1.6008888889 +18514 55.0646833333 -1.6074555556 +18515 55.906473077 -3.398525 +18516 55.906296605 -3.4046143306 +18517 55.9057690643 -3.4106389485 +18518 55.9048960612 -3.4165348337 +18519 55.9036868723 -3.4222393447 +18520 55.9021543458 -3.4276918883 +18521 55.9003147639 -3.4328345671 +18522 55.8981876682 -3.4376127976 +18523 55.8957956516 -3.4419758918 +18524 55.8931641159 -3.4458775957 +18525 55.8903210016 -3.4492765804 +18526 55.8872964889 -3.452136878 +18527 55.8841226767 -3.4544282614 +18528 55.8808332402 -3.4561265595 +18529 55.877463073 -3.4572139095 +18530 55.8740479158 -3.4576789395 +18531 55.8706239771 -3.4575168832 +18532 55.867227549 -3.4567296229 +18533 55.8638946228 -3.4553256631 +18534 55.8606605077 -3.4533200331 +18535 55.8575594574 -3.450734122 +18536 55.8546243084 -3.4475954465 +18537 55.8518861335 -3.4439373541 +18538 55.8493739138 -3.4397986674 +18539 55.8471142336 -3.4352232698 +18540 55.8451310006 -3.4302596402 +18541 55.843445194 -3.4249603402 +18542 55.8420746444 -3.4193814587 +18543 55.8410338464 -3.4135820215 +18544 55.8403338061 -3.40762337 +18545 55.8399819256 -3.4015685166 +18546 55.8399819256 -3.3954814834 +18547 55.8403338061 -3.38942663 +18548 55.8410338464 -3.3834679785 +18549 55.8420746444 -3.3776685413 +18550 55.843445194 -3.3720896598 +18551 55.8451310006 -3.3667903598 +18552 55.8471142336 -3.3618267302 +18553 55.8493739138 -3.3572513326 +18554 55.8518861335 -3.3531126459 +18555 55.8546243084 -3.3494545535 +18556 55.8575594574 -3.346315878 +18557 55.8606605077 -3.3437299669 +18558 55.8638946228 -3.3417243369 +18559 55.867227549 -3.3403203771 +18560 55.8706239771 -3.3395331168 +18561 55.8740479158 -3.3393710605 +18562 55.877463073 -3.3398360905 +18563 55.8808332402 -3.3409234405 +18564 55.8841226767 -3.3426217386 +18565 55.8872964889 -3.344913122 +18566 55.8903210016 -3.3477734196 +18567 55.8931641159 -3.3511724043 +18568 55.8957956516 -3.3550741082 +18569 55.8981876682 -3.3594372024 +18570 55.9003147639 -3.3642154329 +18571 55.9021543458 -3.3693581117 +18572 55.9036868723 -3.3748106553 +18573 55.9048960612 -3.3805151663 +18574 55.9057690643 -3.3864110515 +18575 55.906296605 -3.3924356694 +18576 55.906473077 -3.398525 +18577 55.3049305556 -1.6326027778 +18578 55.2935 -1.6528194444 +18579 55.2888166667 -1.6441694444 +18580 55.2877805556 -1.63475 +18581 55.2953416667 -1.6210055556 +18582 55.2989555556 -1.6220055556 +18583 55.3049305556 -1.6326027778 +18584 56.5324307986 -6.8691666667 +18585 56.5322543409 -6.8753560547 +18586 56.5317268434 -6.8814796627 +18587 56.5308539119 -6.8874724149 +18588 56.5296448231 -6.8932706372 +18589 56.5281124248 -6.898812738 +18590 56.5262729986 -6.9040398665 +18591 56.5241460857 -6.9088965412 +18592 56.5217542778 -6.9133312409 +18593 56.5191229759 -6.9172969527 +18594 56.5162801189 -6.92075167 +18595 56.5132558855 -6.9236588372 +18596 56.5100823723 -6.9259877337 +18597 56.5067932523 -6.9277137958 +18598 56.5034234163 -6.928818872 +18599 56.5000086018 -6.9292914089 +18600 56.4965850139 -6.929126567 +18601 56.4931889409 -6.9283262651 +18602 56.4898563701 -6.9268991521 +18603 56.4866226063 -6.9248605091 +18604 56.4835218989 -6.9222320802 +18605 56.4805870799 -6.9190418369 +18606 56.4778492177 -6.9153236767 +18607 56.4753372889 -6.9111170607 +18608 56.4730778737 -6.9064665928 +18609 56.4710948757 -6.901421547 +18610 56.4694092709 -6.8960353454 +18611 56.4680388867 -6.8903649949 +18612 56.466998215 -6.8844704862 +18613 56.46629826 -6.8784141631 +18614 56.4659464225 -6.8722600672 +18615 56.4659464225 -6.8660732661 +18616 56.46629826 -6.8599191702 +18617 56.466998215 -6.8538628471 +18618 56.4680388867 -6.8479683384 +18619 56.4694092709 -6.8422979879 +18620 56.4710948757 -6.8369117864 +18621 56.4730778737 -6.8318667405 +18622 56.4753372889 -6.8272162726 +18623 56.4778492177 -6.8230096566 +18624 56.4805870799 -6.8192914965 +18625 56.4835218989 -6.8161012532 +18626 56.4866226063 -6.8134728243 +18627 56.4898563701 -6.8114341812 +18628 56.4931889409 -6.8100070682 +18629 56.4965850139 -6.8092067663 +18630 56.5000086018 -6.8090419244 +18631 56.5034234163 -6.8095144613 +18632 56.5067932523 -6.8106195375 +18633 56.5100823723 -6.8123455996 +18634 56.5132558855 -6.8146744961 +18635 56.5162801189 -6.8175816633 +18636 56.5191229759 -6.8210363807 +18637 56.5217542778 -6.8250020924 +18638 56.5241460857 -6.8294367922 +18639 56.5262729986 -6.8342934669 +18640 56.5281124248 -6.8395205953 +18641 56.5296448231 -6.8450626961 +18642 56.5308539119 -6.8508609184 +18643 56.5317268434 -6.8568536707 +18644 56.5322543409 -6.8629772786 +18645 56.5324307986 -6.8691666667 +18646 56.4608361111 -6.9317583333 +18647 56.47344325 -6.9072867778 +18648 56.4754483478 -6.9113222392 +18649 56.477646477 -6.9150151454 +18650 56.4800197778 -6.9183354167 +18651 56.4674138889 -6.9428 +18652 56.4608361111 -6.9317583333 +18653 56.5368638889 -6.8076972222 +18654 56.5248960833 -6.83103425 +18655 56.5228900067 -6.8269941803 +18656 56.5206906729 -6.8232981894 +18657 56.5183160278 -6.8199763611 +18658 56.5302861111 -6.7966305556 +18659 56.5368638889 -6.8076972222 +18660 56.5110166667 -6.9593305556 +18661 56.5057391389 -6.9281294444 +18662 56.5086545573 -6.9268188412 +18663 56.5114926778 -6.9250376557 +18664 56.5142303333 -6.9228003333 +18665 56.5196027778 -6.9545611111 +18666 56.5110166667 -6.9593305556 +18667 56.4911138889 -6.7867861111 +18668 56.4949871389 -6.80950325 +18669 56.4920271763 -6.8104304407 +18670 56.4891255438 -6.8118364249 +18671 56.4863058889 -6.8137096111 +18672 56.4825277778 -6.79155 +18673 56.4911138889 -6.7867861111 +18674 56.6353302443 -6.6177444444 +18675 56.635153789 -6.6239506685 +18676 56.6346262985 -6.6300909328 +18677 56.6337533787 -6.6360999842 +18678 56.6325443062 -6.6419139746 +18679 56.6310119287 -6.6474711444 +18680 56.6291725279 -6.6527124825 +18681 56.6270456447 -6.6575823563 +18682 56.6246538708 -6.6620291044 +18683 56.622022607 -6.6660055861 +18684 56.6191797919 -6.6694696809 +18685 56.616155604 -6.6723847342 +18686 56.6129821396 -6.6747199424 +18687 56.6096930713 -6.6764506758 +18688 56.6063232894 -6.6775587344 +18689 56.6029085309 -6.678032534 +18690 56.5994850003 -6.6778672232 +18691 56.5960889855 -6.6770647265 +18692 56.5927564728 -6.6756337175 +18693 56.5895227666 -6.6735895195 +18694 56.5864221154 -6.6709539363 +18695 56.5834873505 -6.6677550161 +18696 56.5807495395 -6.6640267488 +18697 56.5782376584 -6.659808703 +18698 56.5759782867 -6.6551456038 +18699 56.5739953273 -6.650086859 +18700 56.5723097556 -6.6446860355 +18701 56.5709393985 -6.6390002947 +18702 56.5698987475 -6.6330897895 +18703 56.5691988065 -6.6270170324 +18704 56.5688469761 -6.6208462383 +18705 56.5688469761 -6.6146426506 +18706 56.5691988065 -6.6084718565 +18707 56.5698987475 -6.6023990994 +18708 56.5709393985 -6.5964885942 +18709 56.5723097556 -6.5908028534 +18710 56.5739953273 -6.5854020299 +18711 56.5759782867 -6.5803432851 +18712 56.5782376584 -6.5756801859 +18713 56.5807495395 -6.5714621401 +18714 56.5834873505 -6.5677338728 +18715 56.5864221154 -6.5645349526 +18716 56.5895227666 -6.5618993694 +18717 56.5927564728 -6.5598551714 +18718 56.5960889855 -6.5584241624 +18719 56.5994850003 -6.5576216657 +18720 56.6029085309 -6.5574563549 +18721 56.6063232894 -6.5579301545 +18722 56.6096930713 -6.559038213 +18723 56.6129821396 -6.5607689465 +18724 56.616155604 -6.5631041547 +18725 56.6191797919 -6.566019208 +18726 56.622022607 -6.5694833028 +18727 56.6246538708 -6.5734597845 +18728 56.6270456447 -6.5779065326 +18729 56.6291725279 -6.5827764064 +18730 56.6310119287 -6.5880177445 +18731 56.6325443062 -6.5935749143 +18732 56.6337533787 -6.5993889047 +18733 56.6346262985 -6.6053979561 +18734 56.635153789 -6.6115382204 +18735 56.6353302443 -6.6177444444 +18736 56.0908304089 -6.2430777778 +18737 56.0906539411 -6.2491961631 +18738 56.0901264132 -6.2552495257 +18739 56.0892534313 -6.2611735392 +18740 56.0880442721 -6.2669052621 +18741 56.0865117836 -6.2723838114 +18742 56.0846722478 -6.2775510128 +18743 56.0825452064 -6.2823520222 +18744 56.0801532515 -6.2867359094 +18745 56.0775217851 -6.2906562002 +18746 56.0746787469 -6.2940713687 +18747 56.0716543169 -6.2969452767 +18748 56.0684805931 -6.2992475535 +18749 56.0651912502 -6.3009539141 +18750 56.0618211809 -6.3020464118 +18751 56.058406125 -6.302513622 +18752 56.0549822899 -6.3023507571 +18753 56.0515859667 -6.3015597101 +18754 56.0482531455 -6.3001490272 +18755 56.045019134 -6.2981338111 +18756 56.0419181849 -6.2955355538 +18757 56.0389831333 -6.2923819039 +18758 56.0362450506 -6.288706369 +18759 56.0337329167 -6.2845479568 +18760 56.0314733147 -6.27995076 +18761 56.029490151 -6.2749634884 +18762 56.0278044039 -6.2696389535 +18763 56.0264339031 -6.2640335107 +18764 56.0253931423 -6.2582064661 +18765 56.0246931271 -6.252219452 +18766 56.0243412593 -6.24613578 +18767 56.0243412593 -6.2400197755 +18768 56.0246931271 -6.2339361035 +18769 56.0253931423 -6.2279490895 +18770 56.0264339031 -6.2221220449 +18771 56.0278044039 -6.2165166021 +18772 56.029490151 -6.2111920672 +18773 56.0314733147 -6.2062047956 +18774 56.0337329167 -6.2016075988 +18775 56.0362450506 -6.1974491865 +18776 56.0389831333 -6.1937736516 +18777 56.0419181849 -6.1906200018 +18778 56.045019134 -6.1880217445 +18779 56.0482531455 -6.1860065283 +18780 56.0515859667 -6.1845958455 +18781 56.0549822899 -6.1838047984 +18782 56.058406125 -6.1836419335 +18783 56.0618211809 -6.1841091438 +18784 56.0651912502 -6.1852016415 +18785 56.0684805931 -6.1869080021 +18786 56.0716543169 -6.1892102788 +18787 56.0746787469 -6.1920841868 +18788 56.0775217851 -6.1954993554 +18789 56.0801532515 -6.1994196462 +18790 56.0825452064 -6.2038035334 +18791 56.0846722478 -6.2086045427 +18792 56.0865117836 -6.2137717441 +18793 56.0880442721 -6.2192502934 +18794 56.0892534313 -6.2249820164 +18795 56.0901264132 -6.2309060299 +18796 56.0906539411 -6.2369593925 +18797 56.0908304089 -6.2430777778 +18798 56.4969837675 -5.3998638889 +18799 56.496807309 -5.406047503 +18800 56.4962798091 -5.4121653987 +18801 56.4954068736 -5.4181525612 +18802 56.4941977792 -5.4239453758 +18803 56.4926653737 -5.4294823086 +18804 56.4908259387 -5.4347045639 +18805 56.4886990155 -5.439556712 +18806 56.4863071959 -5.4439872797 +18807 56.4836758809 -5.4479492979 +18808 56.4808330094 -5.4514007993 +18809 56.4778087602 -5.4543052619 +18810 56.4746352302 -5.4566319937 +18811 56.4713460924 -5.4583564538 +18812 56.4679762377 -5.4594605072 +18813 56.4645614039 -5.459932611 +18814 56.4611377962 -5.45976793 +18815 56.4577417032 -5.4589683807 +18816 56.4544091123 -5.4575426038 +18817 56.4511753287 -5.4555058658 +18818 56.4480746019 -5.4528798905 +18819 56.4451397644 -5.4496926229 +18820 56.4424018844 -5.445977929 +18821 56.4398899392 -5.4417752329 +18822 56.437630509 -5.4371290969 +18823 56.4356474978 -5.4320887491 +18824 56.4339618815 -5.4267075622 +18825 56.432591488 -5.4210424898 +18826 56.4315508091 -5.4151534672 +18827 56.4308508493 -5.4091027801 +18828 56.4304990094 -5.4029544109 +18829 56.4304990094 -5.3967733668 +18830 56.4308508493 -5.3906249977 +18831 56.4315508091 -5.3845743106 +18832 56.432591488 -5.3786852879 +18833 56.4339618815 -5.3730202156 +18834 56.4356474978 -5.3676390286 +18835 56.437630509 -5.3625986809 +18836 56.4398899392 -5.3579525449 +18837 56.4424018844 -5.3537498487 +18838 56.4451397644 -5.3500351548 +18839 56.4480746019 -5.3468478873 +18840 56.4511753287 -5.3442219119 +18841 56.4544091123 -5.342185174 +18842 56.4577417032 -5.3407593971 +18843 56.4611377962 -5.3399598478 +18844 56.4645614039 -5.3397951668 +18845 56.4679762377 -5.3402672706 +18846 56.4713460924 -5.341371324 +18847 56.4746352302 -5.3430957841 +18848 56.4778087602 -5.3454225159 +18849 56.4808330094 -5.3483269785 +18850 56.4836758809 -5.3517784799 +18851 56.4863071959 -5.3557404981 +18852 56.4886990155 -5.3601710658 +18853 56.4908259387 -5.3650232139 +18854 56.4926653737 -5.3702454692 +18855 56.4941977792 -5.375782402 +18856 56.4954068736 -5.3815752166 +18857 56.4962798091 -5.3875623791 +18858 56.496807309 -5.3936802747 +18859 56.4969837675 -5.3998638889 +18860 56.4140361111 -5.4004833333 +18861 56.4304789167 -5.3975838056 +18862 56.4305003651 -5.4030012099 +18863 56.4307920761 -5.4083931319 +18864 56.4313516944 -5.4137157778 +18865 56.4149083333 -5.4166083333 +18866 56.4140361111 -5.4004833333 +18867 56.5127111111 -5.3993666667 +18868 56.4969597222 -5.4021495278 +18869 56.4969383259 -5.3967225023 +18870 56.4966461693 -5.3913211261 +18871 56.4960856389 -5.3859895 +18872 56.5118361111 -5.3832 +18873 56.5127111111 -5.3993666667 +18874 56.4743894449 -3.3739055556 +18875 56.4742129859 -3.3800854962 +18876 56.4736854844 -3.3861997576 +18877 56.4728125464 -3.3921833637 +18878 56.4716034484 -3.3979727379 +18879 56.4700710383 -3.4035063827 +18880 56.4682315978 -3.4087255376 +18881 56.466104668 -3.4135748057 +18882 56.4637128409 -3.4180027446 +18883 56.4610815175 -3.4219624129 +18884 56.4582386368 -3.4254118681 +18885 56.4552143776 -3.42831461 +18886 56.4520408369 -3.4306399647 +18887 56.4487516877 -3.4323634055 +18888 56.4453818211 -3.4334668082 +18889 56.4419669749 -3.4339386364 +18890 56.4385433546 -3.4337740577 +18891 56.4351472489 -3.4329749872 +18892 56.4318146452 -3.4315500604 +18893 56.4285808489 -3.4295145345 +18894 56.4254801098 -3.4268901202 +18895 56.4225452604 -3.4237047459 +18896 56.4198073692 -3.4199922572 +18897 56.4172954134 -3.415792055 +18898 56.4150359737 -3.4111486751 +18899 56.413052954 -3.4061113164 +18900 56.4113673305 -3.4007333198 +18901 56.409996931 -3.3950716055 +18902 56.4089562476 -3.3891860732 +18903 56.4082562846 -3.3831389719 +18904 56.4079044432 -3.3769942462 +18905 56.4079044432 -3.3708168649 +18906 56.4082562846 -3.3646721392 +18907 56.4089562476 -3.3586250379 +18908 56.409996931 -3.3527395056 +18909 56.4113673305 -3.3470777913 +18910 56.413052954 -3.3416997947 +18911 56.4150359737 -3.336662436 +18912 56.4172954134 -3.3320190561 +18913 56.4198073692 -3.3278188539 +18914 56.4225452604 -3.3241063652 +18915 56.4254801098 -3.3209209909 +18916 56.4285808489 -3.3182965766 +18917 56.4318146452 -3.3162610507 +18918 56.4351472489 -3.3148361239 +18919 56.4385433546 -3.3140370534 +18920 56.4419669749 -3.3138724747 +18921 56.4453818211 -3.314344303 +18922 56.4487516877 -3.3154477056 +18923 56.4520408369 -3.3171711464 +18924 56.4552143776 -3.3194965011 +18925 56.4582386368 -3.322399243 +18926 56.4610815175 -3.3258486983 +18927 56.4637128409 -3.3298083665 +18928 56.466104668 -3.3342363054 +18929 56.4682315978 -3.3390855735 +18930 56.4700710383 -3.3443047284 +18931 56.4716034484 -3.3498383732 +18932 56.4728125464 -3.3556277474 +18933 56.4736854844 -3.3616113535 +18934 56.4742129859 -3.3677256149 +18935 56.4743894449 -3.3739055556 +18936 56.3960916667 -3.4084972222 +18937 56.4099819444 -3.3949996667 +18938 56.4111619804 -3.3999783657 +18939 56.4125858503 -3.4047452434 +18940 56.4142419722 -3.4092615556 +18941 56.4003555556 -3.42275 +18942 56.3960916667 -3.4084972222 +18943 56.4861444444 -3.3392388889 +18944 56.4722648056 -3.3527793333 +18945 56.4710829467 -3.3477937836 +18946 56.4696569316 -3.3430213946 +18947 56.4679984167 -3.3385010833 +18948 56.4818805556 -3.3249527778 +18949 56.4861444444 -3.3392388889 +18950 56.4317694444 -3.4554361111 +18951 56.4321758611 -3.4317364167 +18952 56.4351170685 -3.4329649966 +18953 56.4381078709 -3.4337073317 +18954 56.4411236389 -3.4339572222 +18955 56.4407472222 -3.4559194444 +18956 56.4317694444 -3.4554361111 +18957 56.4435527778 -3.2863305556 +18958 56.4431115278 -3.3139595278 +18959 56.4400935224 -3.3138835923 +18960 56.4370841262 -3.3143017912 +18961 56.4341081111 -3.3152105556 +18962 56.4345777778 -3.2858444444 +18963 56.4435527778 -3.2863305556 +18964 56.47875 -3.419075 +18965 56.4684703889 -3.4081112778 +18966 56.4700697543 -3.4035104538 +18967 56.4714324112 -3.3986671264 +18968 56.4725471944 -3.3936209444 +18969 56.4833083333 -3.4050944444 +18970 56.47875 -3.419075 +18971 56.401125 -3.3176638889 +18972 56.4163559722 -3.3338338333 +18973 56.4144523496 -3.3380343685 +18974 56.4127666313 -3.3425274864 +18975 56.4113125833 -3.3472765278 +18976 56.3965638889 -3.3316138889 +18977 56.401125 -3.3176638889 +18978 56.4857643835 -3.0258333333 +18979 56.4855879248 -3.0320151227 +18980 56.4850604241 -3.0381312131 +18981 56.4841874874 -3.044116609 +18982 56.4829783912 -3.0499077146 +18983 56.4814459834 -3.0554430142 +18984 56.4796065457 -3.0606637293 +18985 56.4774796192 -3.0655144468 +18986 56.4750877959 -3.0699437087 +18987 56.4724564767 -3.0739045596 +18988 56.4696136006 -3.0773550446 +18989 56.4665893465 -3.0802586524 +18990 56.4634158112 -3.0825847002 +18991 56.4601266677 -3.084308654 +18992 56.4567568071 -3.0854123841 +18993 56.4533419671 -3.085884351 +18994 56.4499183532 -3.0857197208 +18995 56.4465222539 -3.0849204094 +18996 56.4431896566 -3.0834950548 +18997 56.4399558667 -3.0814589189 +18998 56.4368551338 -3.078833719 +18999 56.4339202903 -3.0756473919 +19000 56.4311824048 -3.0719337934 +19001 56.4286704544 -3.067732336 +19002 56.4264110194 -3.0630875691 +19003 56.424428004 -3.0580487061 +19004 56.4227423841 -3.052669104 +19005 56.4213719876 -3.0470056997 +19006 56.4203313065 -3.0411184109 +19007 56.4196313452 -3.035069505 +19008 56.4192795045 -3.0289229457 +19009 56.4192795045 -3.022743721 +19010 56.4196313452 -3.0165971617 +19011 56.4203313065 -3.0105482558 +19012 56.4213719876 -3.0046609669 +19013 56.4227423841 -2.9989975627 +19014 56.424428004 -2.9936179605 +19015 56.4264110194 -2.9885790975 +19016 56.4286704544 -2.9839343306 +19017 56.4311824048 -2.9797328733 +19018 56.4339202903 -2.9760192748 +19019 56.4368551338 -2.9728329477 +19020 56.4399558667 -2.9702077478 +19021 56.4431896566 -2.9681716119 +19022 56.4465222539 -2.9667462573 +19023 56.4499183532 -2.9659469459 +19024 56.4533419671 -2.9657823156 +19025 56.4567568071 -2.9662542826 +19026 56.4601266677 -2.9673580127 +19027 56.4634158112 -2.9690819665 +19028 56.4665893465 -2.9714080142 +19029 56.4696136006 -2.9743116221 +19030 56.4724564767 -2.9777621071 +19031 56.4750877959 -2.981722958 +19032 56.4774796192 -2.9861522199 +19033 56.4796065457 -2.9910029373 +19034 56.4814459834 -2.9962236525 +19035 56.4829783912 -3.001758952 +19036 56.4841874874 -3.0075500577 +19037 56.4850604241 -3.0135354536 +19038 56.4855879248 -3.0196515439 +19039 56.4857643835 -3.0258333333 +19040 56.44835 -3.1183416667 +19041 56.4482048333 -3.0853967222 +19042 56.4511958568 -3.0858557268 +19043 56.4541976161 -3.0858259999 +19044 56.4571856667 -3.0853076667 +19045 56.4573305556 -3.1181916667 +19046 56.44835 -3.1183416667 +19047 56.4564027778 -2.9333166667 +19048 56.4565880278 -2.9662158889 +19049 56.4535952763 -2.9657954518 +19050 56.4505937216 -2.9658639633 +19051 56.4476078056 -2.96642075 +19052 56.4474222222 -2.9334611111 +19053 56.4564027778 -2.9333166667 +19054 56.4164726416 -2.8587805556 +19055 56.4162950721 -2.8657021278 +19056 56.4157638834 -2.8725644557 +19057 56.4148836221 -2.8793088068 +19058 56.4136618219 -2.8858774683 +19059 56.4121089388 -2.8922142449 +19060 56.4102382607 -2.8982649438 +19061 56.4080657928 -2.9039778414 +19062 56.4056101194 -2.9093041281 +19063 56.4028922436 -2.9141983267 +19064 56.3999354065 -2.9186186821 +19065 56.3967648868 -2.9225275174 +19066 56.3934077838 -2.9258915536 +19067 56.3898927841 -2.9286821919 +19068 56.3862499157 -2.9308757535 +19069 56.38251029 -2.9324536776 +19070 56.3787058356 -2.9334026742 +19071 56.3748690254 -2.9337148321 +19072 56.3710325982 -2.9333876794 +19073 56.3672292802 -2.9324241985 +19074 56.3634915053 -2.9308327941 +19075 56.3598511391 -2.9286272151 +19076 56.356339208 -2.9258264316 +19077 56.3529856353 -2.9224544677 +19078 56.3498189875 -2.9185401925 +19079 56.3468662319 -2.9141170699 +19080 56.3441525083 -2.9092228713 +19081 56.3417009165 -2.9038993517 +19082 56.3395323205 -2.8981918941 +19083 56.3376651727 -2.8921491227 +19084 56.3361153582 -2.8858224914 +19085 56.3348960602 -2.8792658473 +19086 56.3340176497 -2.8725349765 +19087 56.3334875974 -2.8656871329 +19088 56.333310411 -2.8587805556 +19089 56.3334875974 -2.8518739782 +19090 56.3340176497 -2.8450261346 +19091 56.3348960602 -2.8382952638 +19092 56.3361153582 -2.8317386198 +19093 56.3376651727 -2.8254119884 +19094 56.3395323205 -2.8193692171 +19095 56.3417009165 -2.8136617594 +19096 56.3441525083 -2.8083382398 +19097 56.3468662319 -2.8034440412 +19098 56.3498189875 -2.7990209186 +19099 56.3529856353 -2.7951066434 +19100 56.356339208 -2.7917346795 +19101 56.3598511391 -2.788933896 +19102 56.3634915053 -2.786728317 +19103 56.3672292802 -2.7851369126 +19104 56.3710325982 -2.7841734317 +19105 56.3748690254 -2.783846279 +19106 56.3787058356 -2.7841584369 +19107 56.38251029 -2.7851074336 +19108 56.3862499157 -2.7866853576 +19109 56.3898927841 -2.7888789192 +19110 56.3934077838 -2.7916695575 +19111 56.3967648868 -2.7950335937 +19112 56.3999354065 -2.798942429 +19113 56.4028922436 -2.8033627844 +19114 56.4056101194 -2.808256983 +19115 56.4080657928 -2.8135832697 +19116 56.4102382607 -2.8192961673 +19117 56.4121089388 -2.8253468662 +19118 56.4136618219 -2.8316836428 +19119 56.4148836221 -2.8382523043 +19120 56.4157638834 -2.8449966554 +19121 56.4162950721 -2.8518589833 +19122 56.4164726416 -2.8587805556 +19123 56.3325690833 -2.9144206944 +19124 56.3412401944 -2.9027777778 +19125 56.3430960833 -2.9070505126 +19126 56.3451187835 -2.9110705021 +19127 56.3472976944 -2.9148166667 +19128 56.33794275 -2.9273748889 +19129 56.3325690833 -2.9144206944 +19130 56.4190974444 -2.8181688333 +19131 56.4125516667 -2.8269991944 +19132 56.4111759222 -2.8221647812 +19133 56.4096095711 -2.8175231097 +19134 56.4078608611 -2.8130985833 +19135 56.4137238333 -2.8051870833 +19136 56.4190974444 -2.8181688333 +19137 56.3625036111 -2.9562513333 +19138 56.36452075 -2.9313368611 +19139 56.3674495154 -2.9324977062 +19140 56.370417093 -2.9332753622 +19141 56.3734080556 -2.9336656944 +19142 56.3713919722 -2.9585670556 +19143 56.3625036111 -2.9562513333 +19144 56.3872223611 -2.7612772778 +19145 56.3852410278 -2.7861945833 +19146 56.3823112446 -2.7850416753 +19147 56.3793429756 -2.7842725202 +19148 56.3763516667 -2.7838910278 +19149 56.3783340278 -2.7589605833 +19150 56.3872223611 -2.7612772778 +19151 57.0560390985 -7.4430555556 +19152 57.0558626526 -7.4493317926 +19153 57.0553351905 -7.455541323 +19154 57.054462318 -7.4616181547 +19155 57.0532533114 -7.4674977172 +19156 57.0517210185 -7.473117552 +19157 57.0498817204 -7.478417981 +19158 57.0477549579 -7.4833427432 +19159 57.045363322 -7.4878395942 +19160 57.0427322129 -7.491860862 +19161 57.0398895683 -7.4953639526 +19162 57.0368655654 -7.4983117994 +19163 57.0336922995 -7.5006732542 +19164 57.0304034414 -7.5024234124 +19165 57.0270338796 -7.5035438719 +19166 57.0236193492 -7.5040229219 +19167 57.0201960523 -7.5038556597 +19168 57.0168002742 -7.5030440356 +19169 57.0134679986 -7.5015968243 +19170 57.0102345269 -7.499529525 +19171 57.0071341048 -7.4968641904 +19172 57.0041995606 -7.4936291869 +19173 57.0014619587 -7.4898588892 +19174 56.9989502723 -7.4855933127 +19175 56.996691078 -7.4808776867 +19176 56.9947082762 -7.4757619752 +19177 56.9930228397 -7.4703003474 +19178 56.9916525934 -7.4645506066 +19179 56.9906120271 -7.4585735812 +19180 56.9899121433 -7.4524324849 +19181 56.9895603417 -7.4461922524 +19182 56.9895603417 -7.4399188587 +19183 56.9899121433 -7.4336786262 +19184 56.9906120271 -7.4275375299 +19185 56.9916525934 -7.4215605045 +19186 56.9930228397 -7.4158107637 +19187 56.9947082762 -7.410349136 +19188 56.996691078 -7.4052334244 +19189 56.9989502723 -7.4005177984 +19190 57.0014619587 -7.3962522219 +19191 57.0041995606 -7.3924819242 +19192 57.0071341048 -7.3892469207 +19193 57.0102345269 -7.3865815861 +19194 57.0134679986 -7.3845142869 +19195 57.0168002742 -7.3830670755 +19196 57.0201960523 -7.3822554514 +19197 57.0236193492 -7.3820881892 +19198 57.0270338796 -7.3825672392 +19199 57.0304034414 -7.3836876987 +19200 57.0336922995 -7.3854378569 +19201 57.0368655654 -7.3877993117 +19202 57.0398895683 -7.3907471585 +19203 57.0427322129 -7.3942502491 +19204 57.045363322 -7.3982715169 +19205 57.0477549579 -7.4027683679 +19206 57.0498817204 -7.4076931301 +19207 57.0517210185 -7.4129935591 +19208 57.0532533114 -7.4186133939 +19209 57.054462318 -7.4244929564 +19210 57.0553351905 -7.4305697881 +19211 57.0558626526 -7.4367793185 +19212 57.0560390985 -7.4430555556 +19213 57.0023805556 -7.5186611111 +19214 57.0075711389 -7.4972838889 +19215 57.0103081042 -7.4995843138 +19216 57.0131473248 -7.5014219593 +19217 57.0160655556 -7.5027816667 +19218 57.0105888889 -7.5253361111 +19219 57.0023805556 -7.5186611111 +19220 57.049925 -7.3628166667 +19221 57.0424367222 -7.39384875 +19222 57.039929051 -7.3907906377 +19223 57.0372808229 -7.3881615015 +19224 57.0345137778 -7.3859828056 +19225 57.0417166667 -7.3561305556 +19226 57.049925 -7.3628166667 +19227 57.0285111111 -7.5307805556 +19228 57.02575225 -7.5037998333 +19229 57.0287291903 -7.5030623655 +19230 57.0316576943 -7.5018352022 +19231 57.0345138611 -7.50012825 +19232 57.0373361111 -7.5277277778 +19233 57.0285111111 -7.5307805556 +19234 57.0197555556 -7.3568277778 +19235 57.0223684167 -7.3820743056 +19236 57.0193695108 -7.3823931586 +19237 57.0163985197 -7.3832066545 +19238 57.0134796667 -7.3845080556 +19239 57.0109305556 -7.3598777778 +19240 57.0197555556 -7.3568277778 +19241 57.0565277778 -7.5068583333 +19242 57.0449058333 -7.4886011111 +19243 57.047054711 -7.4847575404 +19244 57.0490058771 -7.4805738096 +19245 57.0507434167 -7.476084 +19246 57.0623611111 -7.4943305556 +19247 57.0565277778 -7.5068583333 +19248 56.9891388889 -7.3795888889 +19249 57.0006344167 -7.3975619444 +19250 56.9984881114 -7.4014054781 +19251 56.9965394753 -7.4055874261 +19252 56.9948043333 -7.41007375 +19253 56.9833055556 -7.3920916667 +19254 56.9891388889 -7.3795888889 +19255 57.5138144373 -7.3638888889 +19256 57.5136380016 -7.370243523 +19257 57.5131105699 -7.376530614 +19258 57.512237748 -7.3826833427 +19259 57.5110288122 -7.3886363291 +19260 57.50949661 -7.3943263326 +19261 57.5076574223 -7.3996929278 +19262 57.5055307894 -7.4046791501 +19263 57.5031393019 -7.4092321026 +19264 57.5005083591 -7.4133035183 +19265 57.4976658978 -7.4168502725 +19266 57.4946420944 -7.4198348381 +19267 57.4914690423 -7.4222256804 +19268 57.488180411 -7.4239975874 +19269 57.4848110868 -7.4251319309 +19270 57.4813968027 -7.425616858 +19271 57.4779737584 -7.425447409 +19272 57.4745782363 -7.4246255628 +19273 57.4712462172 -7.4231602077 +19274 57.4680129995 -7.42106704 +19275 57.4649128256 -7.4183683908 +19276 57.4619785206 -7.4150929832 +19277 57.4592411455 -7.4112756225 +19278 57.4567296703 -7.4069568246 +19279 57.4544706685 -7.4021823834 +19280 57.4524880377 -7.3970028855 +19281 57.450802748 -7.3914731746 +19282 57.4494326221 -7.3856517729 +19283 57.4483921478 -7.3796002648 +19284 57.4476923261 -7.3733826489 +19285 57.4473405559 -7.3670646665 +19286 57.4473405559 -7.3607131113 +19287 57.4476923261 -7.3543951289 +19288 57.4483921478 -7.348177513 +19289 57.4494326221 -7.3421260049 +19290 57.450802748 -7.3363046032 +19291 57.4524880377 -7.3307748923 +19292 57.4544706685 -7.3255953944 +19293 57.4567296703 -7.3208209532 +19294 57.4592411455 -7.3165021552 +19295 57.4619785206 -7.3126847946 +19296 57.4649128256 -7.3094093869 +19297 57.4680129995 -7.3067107378 +19298 57.4712462172 -7.3046175701 +19299 57.4745782363 -7.303152215 +19300 57.4779737584 -7.3023303687 +19301 57.4813968027 -7.3021609198 +19302 57.4848110868 -7.3026458469 +19303 57.488180411 -7.3037801904 +19304 57.4914690423 -7.3055520973 +19305 57.4946420944 -7.3079429397 +19306 57.4976658978 -7.3109275052 +19307 57.5005083591 -7.3144742595 +19308 57.5031393019 -7.3185456752 +19309 57.5055307894 -7.3230986276 +19310 57.5076574223 -7.32808485 +19311 57.50949661 -7.3334514452 +19312 57.5110288122 -7.3391414487 +19313 57.512237748 -7.3450944351 +19314 57.5131105699 -7.3512471638 +19315 57.5136380016 -7.3575342548 +19316 57.5138144373 -7.3638888889 +19317 57.4478472222 -7.4375166667 +19318 57.4582158611 -7.4096192222 +19319 57.460527276 -7.4131712731 +19320 57.46300177 -7.4163226737 +19321 57.4656192222 -7.4190477222 +19322 57.4552444444 -7.4469583333 +19323 57.4478472222 -7.4375166667 +19324 57.5148805556 -7.2860777778 +19325 57.5029787222 -7.31827175 +19326 57.5006722278 -7.3147038122 +19327 57.4982018809 -7.3115371197 +19328 57.4955878333 -7.3087974167 +19329 57.5074833333 -7.2766166667 +19330 57.5148805556 -7.2860777778 +19331 57.5296843333 -7.3926600556 +19332 57.5118143889 -7.3849875 +19333 57.5127115306 -7.379665191 +19334 57.5133465673 -7.3742140602 +19335 57.5137143056 -7.3686786111 +19336 57.53170225 -7.3763938333 +19337 57.5296843333 -7.3926600556 +19338 57.4336456389 -7.3344309722 +19339 57.4496147778 -7.3412491111 +19340 57.4486412763 -7.3465157972 +19341 57.4479274827 -7.3519236088 +19342 57.4474791944 -7.3574286111 +19343 57.4316276944 -7.3506536944 +19344 57.4336456389 -7.3344309722 +19345 57.5840676082 -4.0475444444 +19346 57.5838900633 -4.0546862389 +19347 57.5833589483 -4.0617668949 +19348 57.5824788098 -4.0687258029 +19349 57.5812571816 -4.0755034058 +19350 57.5797045197 -4.0820417136 +19351 57.577834112 -4.088284804 +19352 57.5756619633 -4.0941793039 +19353 57.5732066576 -4.0996748488 +19354 57.5704891971 -4.104724515 +19355 57.5675328218 -4.1092852208 +19356 57.564362809 -4.1133180947 +19357 57.5610062559 -4.1167888052 +19358 57.5574918464 -4.1196678512 +19359 57.5538496052 -4.1219308101 +19360 57.5501106398 -4.123558541 +19361 57.5463068745 -4.1245373428 +19362 57.5424707767 -4.1248590642 +19363 57.5386350794 -4.1245211671 +19364 57.5348325024 -4.1235267406 +19365 57.5310954725 -4.1218844678 +19366 57.527455848 -4.1196085452 +19367 57.5239446474 -4.1167185551 +19368 57.520591786 -4.1132392927 +19369 57.5174258222 -4.1092005504 +19370 57.5144737151 -4.1046368596 +19371 57.5117605968 -4.0995871934 +19372 57.5093095592 -4.0940946335 +19373 57.5071414595 -4.0882060019 +19374 57.5052747435 -4.0819714634 +19375 57.5037252905 -4.0754440997 +19376 57.5025062791 -4.0686794606 +19377 57.501628076 -4.0617350944 +19378 57.5010981493 -4.0546700632 +19379 57.500921005 -4.0475444444 +19380 57.5010981493 -4.0404188257 +19381 57.501628076 -4.0333537944 +19382 57.5025062791 -4.0264094283 +19383 57.5037252905 -4.0196447892 +19384 57.5052747435 -4.0131174255 +19385 57.5071414595 -4.006882887 +19386 57.5093095592 -4.0009942554 +19387 57.5117605968 -3.9955016955 +19388 57.5144737151 -3.9904520293 +19389 57.5174258222 -3.9858883385 +19390 57.520591786 -3.9818495962 +19391 57.5239446474 -3.9783703338 +19392 57.527455848 -3.9754803436 +19393 57.5310954725 -3.9732044211 +19394 57.5348325024 -3.9715621483 +19395 57.5386350794 -3.9705677217 +19396 57.5424707767 -3.9702298247 +19397 57.5463068745 -3.9705515461 +19398 57.5501106398 -3.9715303479 +19399 57.5538496052 -3.9731580788 +19400 57.5574918464 -3.9754210377 +19401 57.5610062559 -3.9783000837 +19402 57.564362809 -3.9817707942 +19403 57.5675328218 -3.9858036681 +19404 57.5704891971 -3.9903643739 +19405 57.5732066576 -3.99541404 +19406 57.5756619633 -4.000909585 +19407 57.577834112 -4.0068040849 +19408 57.5797045197 -4.0130471752 +19409 57.5812571816 -4.0195854831 +19410 57.5824788098 -4.026363086 +19411 57.5833589483 -4.033321994 +19412 57.5838900633 -4.04040265 +19413 57.5840676082 -4.0475444444 +19414 57.5047583333 -4.1166388889 +19415 57.5122078611 -4.1004858611 +19416 57.5143384338 -4.1044062774 +19417 57.5166154193 -4.1080315965 +19418 57.519027 -4.1113429444 +19419 57.5115833333 -4.1274805556 +19420 57.5047583333 -4.1166388889 +19421 57.580575 -3.9774833333 +19422 57.5727610833 -3.9945199444 +19423 57.5706269755 -3.990598808 +19424 57.5683464492 -3.9869746432 +19425 57.5659313889 -3.9836663056 +19426 57.57375 -3.9666166667 +19427 57.580575 -3.9774833333 +19428 57.5554416667 -4.1413694444 +19429 57.5519122778 -4.1228588611 +19430 57.5548065424 -4.1214032257 +19431 57.5576368626 -4.119563074 +19432 57.5603885 -4.1173478889 +19433 57.5639 -4.1357638889 +19434 57.5554416667 -4.1413694444 +19435 57.5316694444 -3.9673888889 +19436 57.532641 -3.9724428889 +19437 57.5297563839 -3.9739612196 +19438 57.5269380967 -3.9758618079 +19439 57.5242007778 -3.9781346944 +19440 57.5232111111 -3.9729861111 +19441 57.5316694444 -3.9673888889 +19442 57.7482304105 -3.3378888889 +19443 57.7480528689 -3.3450630202 +19444 57.747521764 -3.352175735 +19445 57.7466416423 -3.3591661478 +19446 57.7454200376 -3.365974431 +19447 57.7438674061 -3.3725423308 +19448 57.7419970354 -3.3788136709 +19449 57.7398249306 -3.3847348362 +19450 57.7373696753 -3.3902552337 +19451 57.734652272 -3.3953277273 +19452 57.7316959604 -3.3999090406 +19453 57.7285260175 -3.4039601267 +19454 57.7251695403 -3.4074464995 +19455 57.7216552125 -3.4103385256 +19456 57.7180130581 -3.4126116729 +19457 57.7142741844 -3.4142467157 +19458 57.7104705148 -3.4152298924 +19459 57.7066345159 -3.4155530167 +19460 57.7027989203 -3.4152135405 +19461 57.6989964465 -3.4142145688 +19462 57.6952595206 -3.4125648257 +19463 57.6916199997 -3.4102785734 +19464 57.6881089011 -3.4073754839 +19465 57.6847561392 -3.4038804661 +19466 57.6815902711 -3.3998234477 +19467 57.6786382549 -3.3952391168 +19468 57.6759252214 -3.3901666232 +19469 57.6734742616 -3.3846492432 +19470 57.6713062315 -3.3787340102 +19471 57.6694395761 -3.3724713151 +19472 57.6678901739 -3.3659144786 +19473 57.6666712026 -3.3591193005 +19474 57.6657930287 -3.352143588 +19475 57.6652631197 -3.3450466683 +19476 57.6650859813 -3.3378888889 +19477 57.6652631197 -3.3307311095 +19478 57.6657930287 -3.3236341898 +19479 57.6666712026 -3.3166584773 +19480 57.6678901739 -3.3098632992 +19481 57.6694395761 -3.3033064627 +19482 57.6713062315 -3.2970437676 +19483 57.6734742616 -3.2911285346 +19484 57.6759252214 -3.2856111546 +19485 57.6786382549 -3.280538661 +19486 57.6815902711 -3.2759543301 +19487 57.6847561392 -3.2718973117 +19488 57.6881089011 -3.2684022939 +19489 57.6916199997 -3.2654992044 +19490 57.6952595206 -3.2632129521 +19491 57.6989964465 -3.261563209 +19492 57.7027989203 -3.2605642373 +19493 57.7066345159 -3.2602247611 +19494 57.7104705148 -3.2605478854 +19495 57.7142741844 -3.2615310621 +19496 57.7180130581 -3.2631661049 +19497 57.7216552125 -3.2654392522 +19498 57.7251695403 -3.2683312783 +19499 57.7285260175 -3.2718176511 +19500 57.7316959604 -3.2758687372 +19501 57.734652272 -3.2804500505 +19502 57.7373696753 -3.285522544 +19503 57.7398249306 -3.2910429416 +19504 57.7419970354 -3.2969641068 +19505 57.7438674061 -3.303235447 +19506 57.7454200376 -3.3098033468 +19507 57.7466416423 -3.3166116299 +19508 57.747521764 -3.3236020428 +19509 57.7480528689 -3.3307147576 +19510 57.7482304105 -3.3378888889 +19511 57.6623962222 -3.4052303889 +19512 57.6736762778 -3.3851451111 +19513 57.6755851141 -3.3894605228 +19514 57.6776554804 -3.3935083929 +19515 57.6798766389 -3.3972676667 +19516 57.6686000833 -3.4173429722 +19517 57.6623962222 -3.4052303889 +19518 57.7508905278 -3.2704251389 +19519 57.7396351944 -3.2905774444 +19520 57.7377241466 -3.2862578363 +19521 57.7356514462 -3.2822074459 +19522 57.7334278889 -3.2784473611 +19523 57.74468675 -3.2582850556 +19524 57.7508905278 -3.2704251389 +19525 57.7077121111 -3.4264832778 +19526 57.7070576667 -3.4155498889 +19527 57.7100528307 -3.4152973401 +19528 57.7130304583 -3.4146420388 +19529 57.7159750556 -3.4135873056 +19530 57.716634 -3.4245959444 +19531 57.7077121111 -3.4264832778 +19532 57.7047635833 -3.2287245833 +19533 57.7066935278 -3.2602247222 +19534 57.7036972473 -3.260425149 +19535 57.7007164886 -3.2610283953 +19536 57.69776675 -3.2620312222 +19537 57.6958416944 -3.2306113056 +19538 57.7047635833 -3.2287245833 +19539 57.2440754236 -2.1980555556 +19540 57.2438978716 -2.2051314822 +19541 57.2433667355 -2.2121468371 +19542 57.2424865618 -2.2190415719 +19543 57.2412648843 -2.2257566814 +19544 57.239712159 -2.2322347123 +19545 57.2378416738 -2.2384202596 +19546 57.2356694335 -2.2442604437 +19547 57.2332140222 -2.249705365 +19548 57.2304964423 -2.2547085326 +19549 57.2275399342 -2.2592272616 +19550 57.2243697755 -2.2632230376 +19551 57.221013064 -2.266661844 +19552 57.2174984844 -2.2695144494 +19553 57.2138560622 -2.2717566538 +19554 57.2101169061 -2.2733694897 +19555 57.2063129417 -2.2743393788 +19556 57.2024766378 -2.2746582417 +19557 57.1986407293 -2.2743235599 +19558 57.1948379377 -2.2733383906 +19559 57.1911006919 -2.2717113336 +19560 57.1874608524 -2.2694564514 +19561 57.1839494398 -2.2665931431 +19562 57.180596372 -2.2631459735 +19563 57.1774302095 -2.2591444585 +19564 57.174477914 -2.2546228104 +19565 57.1717646198 -2.2496196428 +19566 57.1693134211 -2.2441776406 +19567 57.1671451771 -2.2383431954 +19568 57.1652783355 -2.2321660113 +19569 57.1637287773 -2.2256986832 +19570 57.1625096825 -2.2189962516 +19571 57.1616314191 -2.2121157379 +19572 57.1611014558 -2.2051156633 +19573 57.1609242992 -2.1980555556 +19574 57.1611014558 -2.1909954478 +19575 57.1616314191 -2.1839953732 +19576 57.1625096825 -2.1771148595 +19577 57.1637287773 -2.1704124279 +19578 57.1652783355 -2.1639450998 +19579 57.1671451771 -2.1577679157 +19580 57.1693134211 -2.1519334705 +19581 57.1717646198 -2.1464914683 +19582 57.174477914 -2.1414883007 +19583 57.1774302095 -2.1369666526 +19584 57.180596372 -2.1329651376 +19585 57.1839494398 -2.129517968 +19586 57.1874608524 -2.1266546597 +19587 57.1911006919 -2.1243997775 +19588 57.1948379377 -2.1227727205 +19589 57.1986407293 -2.1217875512 +19590 57.2024766378 -2.1214528694 +19591 57.2063129417 -2.1217717323 +19592 57.2101169061 -2.1227416214 +19593 57.2138560622 -2.1243544573 +19594 57.2174984844 -2.1265966617 +19595 57.221013064 -2.1294492671 +19596 57.2243697755 -2.1328880735 +19597 57.2275399342 -2.1368838495 +19598 57.2304964423 -2.1414025785 +19599 57.2332140222 -2.1464057461 +19600 57.2356694335 -2.1518506674 +19601 57.2378416738 -2.1576908515 +19602 57.239712159 -2.1638763988 +19603 57.2412648843 -2.1703544298 +19604 57.2424865618 -2.1770695392 +19605 57.2433667355 -2.183964274 +19606 57.2438978716 -2.1909796289 +19607 57.2440754236 -2.1980555556 +19608 57.1699 -2.2558333333 +19609 57.1724325 -2.2509389444 +19610 57.1745835737 -2.2547998124 +19611 57.1768803442 -2.2583651059 +19612 57.1793108611 -2.2616161667 +19613 57.1764083333 -2.267225 +19614 57.1699 -2.2558333333 +19615 57.2412277778 -2.1416416667 +19616 57.2358029722 -2.1521781389 +19617 57.2339182045 -2.1478649411 +19618 57.2318693419 -2.143814412 +19619 57.2296671111 -2.1400476944 +19620 57.2347222222 -2.1302277778 +19621 57.2412277778 -2.1416416667 +19622 57.2341222222 -2.26135 +19623 57.2302386389 -2.2551375556 +19624 57.2323996757 -2.2513035743 +19625 57.2344050786 -2.2471918743 +19626 57.2362443889 -2.2428238611 +19627 57.24 -2.2488305556 +19628 57.2341222222 -2.26135 +19629 57.1681777778 -2.13425 +19630 57.1736382222 -2.1429397222 +19631 57.1715566524 -2.1469152275 +19632 57.1696360549 -2.1511562433 +19633 57.1678863889 -2.1556406944 +19634 57.1622972222 -2.1467444444 +19635 57.1681777778 -2.13425 +19636 57.2505722222 -2.2426722222 +19637 57.2391555278 -2.2342207778 +19638 57.2404748588 -2.2292543468 +19639 57.2415964682 -2.2241251251 +19640 57.2425145 -2.2188598611 +19641 57.2539111111 -2.2272916667 +19642 57.2505722222 -2.2426722222 +19643 57.1542722222 -2.1537638889 +19644 57.1657595833 -2.1622190556 +19645 57.1644531612 -2.1671869666 +19646 57.1633444667 -2.1723149548 +19647 57.16243925 -2.1775764167 +19648 57.1509333333 -2.1691027778 +19649 57.1542722222 -2.1537638889 +19650 57.1597811944 -2.1920326944 +19651 57.1610514167 -2.1920731667 +19652 57.1609250685 -2.1975928553 +19653 57.1610151918 -2.2031149457 +19654 57.1613213333 -2.20861075 +19655 57.1596245 -2.2085559444 +19656 57.1597811944 -2.1920326944 +19657 58.2571659496 -6.3310666667 +19658 58.2569884183 -6.3383433246 +19659 58.2564573442 -6.3455576842 +19660 58.2555772738 -6.3526479856 +19661 58.2543557411 -6.3595535425 +19662 58.2528032022 -6.3662152656 +19663 58.2509329449 -6.3725761731 +19664 58.2487609742 -6.3785818819 +19665 58.2463058737 -6.3841810752 +19666 58.2435886454 -6.3893259432 +19667 58.2406325289 -6.3939725923 +19668 58.2374628007 -6.3980814193 +19669 58.2341065568 -6.4016174482 +19670 58.2305924798 -6.4045506258 +19671 58.2269505926 -6.4068560739 +19672 58.2232120008 -6.4085142969 +19673 58.2194086259 -6.4095113418 +19674 58.2155729323 -6.4098389112 +19675 58.21173765 -6.4094944263 +19676 58.2079354948 -6.4084810417 +19677 58.2041988897 -6.4068076117 +19678 58.2005596887 -6.4044886068 +19679 58.1970489057 -6.4015439844 +19680 58.1936964513 -6.3979990124 +19681 58.1905308793 -6.3938840486 +19682 58.1875791442 -6.3892342779 +19683 58.1848663732 -6.3840894099 +19684 58.182415654 -6.3784933381 +19685 58.1802478395 -6.3724937661 +19686 58.1783813719 -6.3661418016 +19687 58.1768321269 -6.3594915233 +19688 58.1756132803 -6.3525995233 +19689 58.1747351967 -6.3455244289 +19690 58.1742053424 -6.338326409 +19691 58.1740282223 -6.3310666667 +19692 58.1742053424 -6.3238069243 +19693 58.1747351967 -6.3166089044 +19694 58.1756132803 -6.3095338101 +19695 58.1768321269 -6.30264181 +19696 58.1783813719 -6.2959915317 +19697 58.1802478395 -6.2896395673 +19698 58.182415654 -6.2836399953 +19699 58.1848663732 -6.2780439235 +19700 58.1875791442 -6.2728990554 +19701 58.1905308793 -6.2682492848 +19702 58.1936964513 -6.2641343209 +19703 58.1970489057 -6.2605893489 +19704 58.2005596887 -6.2576447265 +19705 58.2041988897 -6.2553257217 +19706 58.2079354948 -6.2536522916 +19707 58.21173765 -6.2526389071 +19708 58.2155729323 -6.2522944221 +19709 58.2194086259 -6.2526219915 +19710 58.2232120008 -6.2536190365 +19711 58.2269505926 -6.2552772594 +19712 58.2305924798 -6.2575827075 +19713 58.2341065568 -6.2605158851 +19714 58.2374628007 -6.264051914 +19715 58.2406325289 -6.268160741 +19716 58.2435886454 -6.2728073901 +19717 58.2463058737 -6.2779522582 +19718 58.2487609742 -6.2835514515 +19719 58.2509329449 -6.2895571602 +19720 58.2528032022 -6.2959180678 +19721 58.2543557411 -6.3025797908 +19722 58.2555772738 -6.3094853477 +19723 58.2564573442 -6.3165756492 +19724 58.2569884183 -6.3237900087 +19725 58.2571659496 -6.3310666667 +19726 58.1854555556 -6.40615 +19727 58.1896305556 -6.3925569167 +19728 58.1920382971 -6.3959452388 +19729 58.1945687406 -6.3989963377 +19730 58.1972087222 -6.4016943056 +19731 58.1932194444 -6.4146805556 +19732 58.1854555556 -6.40615 +19733 58.2427805556 -6.2528305556 +19734 58.2388406389 -6.2657381389 +19735 58.236293013 -6.2627313236 +19736 58.2336375699 -6.2600812359 +19737 58.2308881667 -6.2578016389 +19738 58.2350138889 -6.2442833333 +19739 58.2427805556 -6.2528305556 +19740 58.2686027778 -6.3497055556 +19741 58.2562685833 -6.3473553333 +19742 58.2567821575 -6.3417523051 +19743 58.2570813209 -6.3360935191 +19744 58.2571645 -6.3304085 +19745 58.2694972222 -6.3327527778 +19746 58.2686027778 -6.3497055556 +19747 58.1615194444 -6.3122833333 +19748 58.1749232778 -6.3148175 +19749 58.1744109341 -6.3204085528 +19750 58.174112552 -6.3260548434 +19751 58.1740296944 -6.3317271111 +19752 58.1606222222 -6.3291861111 +19753 58.1615194444 -6.3122833333 +19754 58.4921426198 -3.0930555556 +19755 58.4919662053 -3.0995859271 +19756 58.4914388369 -3.1060468805 +19757 58.4905661205 -3.1123697415 +19758 58.4893573323 -3.1184873162 +19759 58.4878253192 -3.1243346099 +19760 58.4859863618 -3.1298495226 +19761 58.4838599997 -3.1349735122 +19762 58.4814688224 -3.1396522186 +19763 58.4788382279 -3.1438360416 +19764 58.4759961513 -3.1474806671 +19765 58.4729727663 -3.1505475352 +19766 58.4698001639 -3.1530042459 +19767 58.4665120097 -3.1548248976 +19768 58.4631431864 -3.1559903559 +19769 58.459729422 -3.1564884497 +19770 58.4563069112 -3.1563140919 +19771 58.4529119305 -3.1554693256 +19772 58.4495804547 -3.153963294 +19773 58.4463477753 -3.1518121356 +19774 58.4432481279 -3.1490388059 +19775 58.4403143306 -3.1456728272 +19776 58.4375774374 -3.141749971 +19777 58.4350664112 -3.1373118745 +19778 58.4328078191 -3.1324055973 +19779 58.4308255521 -3.1270831219 +19780 58.429140575 -3.1214008035 +19781 58.4277707055 -3.1154187757 +19782 58.4267304272 -3.1092003171 +19783 58.4260307381 -3.1028111861 +19784 58.4256790346 -3.0963189308 +19785 58.4256790346 -3.0897921803 +19786 58.4260307381 -3.083299925 +19787 58.4267304272 -3.0769107941 +19788 58.4277707055 -3.0706923354 +19789 58.429140575 -3.0647103076 +19790 58.4308255521 -3.0590279892 +19791 58.4328078191 -3.0537055138 +19792 58.4350664112 -3.0487992366 +19793 58.4375774374 -3.0443611401 +19794 58.4403143306 -3.0404382839 +19795 58.4432481279 -3.0370723052 +19796 58.4463477753 -3.0342989755 +19797 58.4495804547 -3.0321478171 +19798 58.4529119305 -3.0306417855 +19799 58.4563069112 -3.0297970192 +19800 58.459729422 -3.0296226614 +19801 58.4631431864 -3.0301207552 +19802 58.4665120097 -3.0312862136 +19803 58.4698001639 -3.0331068652 +19804 58.4729727663 -3.0355635759 +19805 58.4759961513 -3.038630444 +19806 58.4788382279 -3.0422750695 +19807 58.4814688224 -3.0464588925 +19808 58.4838599997 -3.0511375989 +19809 58.4859863618 -3.0562615885 +19810 58.4878253192 -3.0617765012 +19811 58.4893573323 -3.0676237949 +19812 58.4905661205 -3.0737413696 +19813 58.4914388369 -3.0800642307 +19814 58.4919662053 -3.086525184 +19815 58.4921426198 -3.0930555556 +19816 58.4857583333 -3.1757638889 +19817 58.4750425556 -3.1485312222 +19818 58.4775976674 -3.1455271826 +19819 58.4800004426 -3.1420951993 +19820 58.4822312778 -3.1382631667 +19821 58.4929305556 -3.16545 +19822 58.4857583333 -3.1757638889 +19823 58.4320166667 -3.0110833333 +19824 58.4425773056 -3.0377739167 +19825 58.4400322635 -3.0408048412 +19826 58.4376407495 -3.0442604972 +19827 58.4354221944 -3.0481126944 +19828 58.4248444444 -3.021375 +19829 58.4320166667 -3.0110833333 +19830 58.9912650259 -2.9004805556 +19831 58.9910886218 -2.9071051505 +19832 58.9905612849 -2.9136593217 +19833 58.9896886208 -2.9200734005 +19834 58.9884799056 -2.9262792201 +19835 58.9869479864 -2.9322108453 +19836 58.9851091435 -2.9378052781 +19837 58.9829829161 -2.9430031308 +19838 58.9805918934 -2.9477492585 +19839 58.9779614726 -2.9519933464 +19840 58.9751195881 -2.9556904427 +19841 58.9720964125 -2.958801434 +19842 58.9689240353 -2.9612934561 +19843 58.9656361206 -2.9631402382 +19844 58.9622675489 -2.9643223745 +19845 58.958854046 -2.9648275234 +19846 58.9554318039 -2.9646505297 +19847 58.9520370964 -2.9637934711 +19848 58.9487058948 -2.9622656278 +19849 58.9454734876 -2.9600833753 +19850 58.9423741067 -2.9572700039 +19851 58.9394405666 -2.9538554649 +19852 58.9367039177 -2.9498760475 +19853 58.9341931194 -2.9453739904 +19854 58.9319347351 -2.9403970317 +19855 58.9299526531 -2.9349979022 +19856 58.9282678349 -2.9292337674 +19857 58.9268980957 -2.9231656248 +19858 58.9258579171 -2.9168576612 +19859 58.9251582953 -2.9103765784 +19860 58.9248066258 -2.9037908931 +19861 58.9248066258 -2.897170218 +19862 58.9251582953 -2.8905845327 +19863 58.9258579171 -2.8841034499 +19864 58.9268980957 -2.8777954863 +19865 58.9282678349 -2.8717273437 +19866 58.9299526531 -2.8659632089 +19867 58.9319347351 -2.8605640794 +19868 58.9341931194 -2.8555871207 +19869 58.9367039177 -2.8510850636 +19870 58.9394405666 -2.8471056462 +19871 58.9423741067 -2.8436911072 +19872 58.9454734876 -2.8408777358 +19873 58.9487058948 -2.8386954833 +19874 58.9520370964 -2.83716764 +19875 58.9554318039 -2.8363105814 +19876 58.958854046 -2.8361335877 +19877 58.9622675489 -2.8366387366 +19878 58.9656361206 -2.8378208729 +19879 58.9689240353 -2.839667655 +19880 58.9720964125 -2.8421596771 +19881 58.9751195881 -2.8452706684 +19882 58.9779614726 -2.8489677647 +19883 58.9805918934 -2.8532118526 +19884 58.9829829161 -2.8579579804 +19885 58.9851091435 -2.863155833 +19886 58.9869479864 -2.8687502658 +19887 58.9884799056 -2.874681891 +19888 58.9896886208 -2.8808877106 +19889 58.9905612849 -2.8873017895 +19890 58.9910886218 -2.8938559607 +19891 58.9912650259 -2.9004805556 +19892 58.9512361111 -2.9965222222 +19893 58.9520225 -2.9637882778 +19894 58.9549946584 -2.9645786005 +19895 58.9579915212 -2.9648472588 +19896 58.9609886944 -2.9645919444 +19897 58.9602027778 -2.9973055556 +19898 58.9512361111 -2.9965222222 +19899 58.9647638889 -2.8023416667 +19900 58.9639711944 -2.8371498056 +19901 58.9609981919 -2.8363708043 +19902 58.9580010211 -2.836113826 +19903 58.9550040833 -2.8363808333 +19904 58.9557972222 -2.8015527778 +19905 58.9647638889 -2.8023416667 +19906 58.9922083333 -2.9713833333 +19907 58.9790798333 -2.9502969444 +19908 58.9813176402 -2.9464099969 +19909 58.9833649721 -2.9421470098 +19910 58.9852050556 -2.9375428056 +19911 58.9979333333 -2.9579805556 +19912 58.9922083333 -2.9713833333 +19913 58.9249138889 -2.8410083333 +19914 58.9341237778 -2.8557253611 +19915 58.9321339146 -2.8600814518 +19916 58.9303553359 -2.8647667919 +19917 58.9288025278 -2.8697431389 +19918 58.9191916667 -2.8543805556 +19919 58.9249138889 -2.8410083333 +19920 49.9787758952 -6.3318986389 +19921 49.9785992755 -6.3372082978 +19922 49.9780712925 -6.3424615574 +19923 49.9771975541 -6.3476026213 +19924 49.9759873407 -6.3525768918 +19925 49.9744535052 -6.3573315533 +19926 49.9726123364 -6.3618161354 +19927 49.9704833849 -6.3659830515 +19928 49.9680892542 -6.3697881047 +19929 49.9654553598 -6.3731909576 +19930 49.9626096581 -6.3761555602 +19931 49.9595823487 -6.3786505308 +19932 49.9564055526 -6.3806494871 +19933 49.9531129705 -6.3821313228 +19934 49.9497395243 -6.3830804283 +19935 49.9463209866 -6.3834868512 +19936 49.9428936002 -6.3833463981 +19937 49.9394936945 -6.3826606734 +19938 49.9361572996 -6.3814370581 +19939 49.9329197657 -6.3796886263 +19940 49.9298153883 -6.3774340024 +19941 49.9268770461 -6.3746971601 +19942 49.9241358536 -6.3715071648 +19943 49.9216208323 -6.3678978635 +19944 49.9193586054 -6.3639075243 +19945 49.9173731162 -6.3595784308 +19946 49.9156853764 -6.3549564343 +19947 49.9143132447 -6.3500904696 +19948 49.913271239 -6.3450320383 +19949 49.9125703833 -6.3398346667 +19950 49.9122180921 -6.3345533424 +19951 49.9122180921 -6.3292439354 +19952 49.9125703833 -6.323962611 +19953 49.913271239 -6.3187652395 +19954 49.9143132447 -6.3137068082 +19955 49.9156853764 -6.3088408435 +19956 49.9173731162 -6.304218847 +19957 49.9193586054 -6.2998897535 +19958 49.9216208323 -6.2958994143 +19959 49.9241358536 -6.2922901129 +19960 49.9268770461 -6.2891001177 +19961 49.9298153883 -6.2863632754 +19962 49.9329197657 -6.2841086515 +19963 49.9361572996 -6.2823602197 +19964 49.9394936945 -6.2811366044 +19965 49.9428936002 -6.2804508797 +19966 49.9463209866 -6.2803104265 +19967 49.9497395243 -6.2807168495 +19968 49.9531129705 -6.2816659549 +19969 49.9564055526 -6.2831477907 +19970 49.9595823487 -6.285146747 +19971 49.9626096581 -6.2876417176 +19972 49.9654553598 -6.2906063202 +19973 49.9680892542 -6.2940091731 +19974 49.9704833849 -6.2978142263 +19975 49.9726123364 -6.3019811424 +19976 49.9744535052 -6.3064657245 +19977 49.9759873407 -6.311220386 +19978 49.9771975541 -6.3161946565 +19979 49.9780712925 -6.3213357204 +19980 49.9785992755 -6.32658898 +19981 49.9787758952 -6.3318986389 +19982 49.9465871643 -6.2917583333 +19983 49.9464105438 -6.297064453 +19984 49.9458825582 -6.3023142112 +19985 49.9450088157 -6.3074518487 +19986 49.9437985963 -6.3124228043 +19987 49.9422647534 -6.3171742977 +19988 49.9404235756 -6.3216558924 +19989 49.9382946135 -6.3258200333 +19990 49.9359004707 -6.3296225531 +19991 49.933266563 -6.3330231412 +19992 49.9304208467 -6.3359857716 +19993 49.9273935215 -6.3384790834 +19994 49.9242167086 -6.3404767119 +19995 49.9209241088 -6.3419575646 +19996 49.9175506443 -6.342906042 +19997 49.9141320877 -6.3433121985 +19998 49.9107046821 -6.343171843 +19999 49.9073047571 -6.3424865789 +20000 49.903968343 -6.341263782 +20001 49.9007307902 -6.3395165174 +20002 49.8976263944 -6.3372633973 +20003 49.8946880347 -6.3345283791 +20004 49.8919468255 -6.3313405088 +20005 49.8894317889 -6.3277336107 +20006 49.887169548 -6.3237459277 +20007 49.8851840465 -6.319419715 +20008 49.8834962961 -6.3148007936 +20009 49.8821241558 -6.3099380657 +20010 49.8810821435 -6.3048829988 +20011 49.8803812834 -6.2996890837 +20012 49.8800289899 -6.2944112715 +20013 49.8800289899 -6.2891053952 +20014 49.8803812834 -6.283827583 +20015 49.8810821435 -6.2786336679 +20016 49.8821241558 -6.273578601 +20017 49.8834962961 -6.268715873 +20018 49.8851840465 -6.2640969517 +20019 49.887169548 -6.259770739 +20020 49.8894317889 -6.2557830559 +20021 49.8919468255 -6.2521761579 +20022 49.8946880347 -6.2489882876 +20023 49.8976263944 -6.2462532693 +20024 49.9007307902 -6.2440001492 +20025 49.903968343 -6.2422528847 +20026 49.9073047571 -6.2410300877 +20027 49.9107046821 -6.2403448236 +20028 49.9141320877 -6.2402044682 +20029 49.9175506443 -6.2406106246 +20030 49.9209241088 -6.2415591021 +20031 49.9242167086 -6.2430399548 +20032 49.9273935215 -6.2450375832 +20033 49.9304208467 -6.2475308951 +20034 49.933266563 -6.2504935255 +20035 49.9359004707 -6.2538941136 +20036 49.9382946135 -6.2576966333 +20037 49.9404235756 -6.2618607743 +20038 49.9422647534 -6.2663423689 +20039 49.9437985963 -6.2710938623 +20040 49.9450088157 -6.276064818 +20041 49.9458825582 -6.2812024554 +20042 49.9464105438 -6.2864522136 +20043 49.9465871643 -6.2917583333 +20044 49.9064916667 -6.3645694444 +20045 49.9072264167 -6.34246425 +20046 49.9102031456 -6.3431052792 +20047 49.9132050721 -6.3433281924 +20048 49.91620775 -6.3431310833 +20049 49.9154722222 -6.3652722222 +20050 49.9064916667 -6.3645694444 +20051 49.9202444444 -6.2192583333 +20052 49.9195422222 -6.2411032222 +20053 49.9165683712 -6.2404376283 +20054 49.9135678841 -6.2401899616 +20055 49.9105651944 -6.2403621389 +20056 49.9112666667 -6.2185527778 +20057 49.9202444444 -6.2192583333 +20058 49.946525 -6.3451222222 +20059 49.9354010833 -6.3303235833 +20060 49.9375560717 -6.3270783713 +20061 49.9395133576 -6.3235450932 +20062 49.9412569722 -6.3197525278 +20063 49.9523777778 -6.3345444444 +20064 49.946525 -6.3451222222 +20065 49.8800277778 -6.2384777778 +20066 49.8911571944 -6.2532298056 +20067 49.8890044172 -6.2564752205 +20068 49.8870493107 -6.2600075139 +20069 49.8853077778 -6.2637979444 +20070 49.874175 -6.2490388889 +20071 49.8800277778 -6.2384777778 +20072 59.2236221598 -2.7724055556 +20073 59.2234457605 -2.7790751247 +20074 59.2229184379 -2.7856737902 +20075 59.2220457978 -2.7921314086 +20076 59.2208371162 -2.7983793486 +20077 59.2193052401 -2.8043512262 +20078 59.2174664497 -2.8099836148 +20079 59.2153402842 -2.8152167228 +20080 59.2129493325 -2.8199950311 +20081 59.2103189917 -2.8242678836 +20082 59.2074771956 -2.8279900241 +20083 59.2044541165 -2.831122075 +20084 59.2012818432 -2.8336309507 +20085 59.1979940389 -2.835490204 +20086 59.1946255834 -2.8366802999 +20087 59.1912122014 -2.8371888152 +20088 59.1877900836 -2.8370105624 +20089 59.1843955025 -2.8361476357 +20090 59.181064428 -2.8346093806 +20091 59.1778321468 -2.832412286 +20092 59.1747328895 -2.8295798019 +20093 59.1717994687 -2.8261420844 +20094 59.1690629331 -2.8221356698 +20095 59.1665522406 -2.8176030839 +20096 59.1642939529 -2.8125923887 +20097 59.1623119567 -2.8071566721 +20098 59.1606272124 -2.8013534865 +20099 59.1592575338 -2.7952442416 +20100 59.1582174015 -2.7888935577 +20101 59.1575178111 -2.7823685869 +20102 59.1571661574 -2.7757383079 +20103 59.1571661574 -2.7690728032 +20104 59.1575178111 -2.7624425242 +20105 59.1582174015 -2.7559175534 +20106 59.1592575338 -2.7495668695 +20107 59.1606272124 -2.7434576246 +20108 59.1623119567 -2.737654439 +20109 59.1642939529 -2.7322187224 +20110 59.1665522406 -2.7272080272 +20111 59.1690629331 -2.7226754413 +20112 59.1717994687 -2.7186690267 +20113 59.1747328895 -2.7152313092 +20114 59.1778321468 -2.7123988252 +20115 59.181064428 -2.7102017305 +20116 59.1843955025 -2.7086634754 +20117 59.1877900836 -2.7078005487 +20118 59.1912122014 -2.7076222959 +20119 59.1946255834 -2.7081308112 +20120 59.1979940389 -2.7093209071 +20121 59.2012818432 -2.7111801604 +20122 59.2044541165 -2.7136890362 +20123 59.2074771956 -2.716821087 +20124 59.2103189917 -2.7205432276 +20125 59.2129493325 -2.72481608 +20126 59.2153402842 -2.7295943883 +20127 59.2174664497 -2.7348274963 +20128 59.2193052401 -2.7404598849 +20129 59.2208371162 -2.7464317625 +20130 59.2220457978 -2.7526797025 +20131 59.2229184379 -2.7591373209 +20132 59.2234457605 -2.7657359864 +20133 59.2236221598 -2.7724055556 +20134 59.1885278961 -2.6415277778 +20135 59.1883514961 -2.648190508 +20136 59.1878241714 -2.6547824075 +20137 59.1869515277 -2.6612334051 +20138 59.1857428411 -2.6674749401 +20139 59.1842109585 -2.6734406968 +20140 59.1823721602 -2.6790673137 +20141 59.1802459854 -2.6842950607 +20142 59.177855023 -2.6890684755 +20143 59.1752246701 -2.6933369539 +20144 59.1723828607 -2.6970552861 +20145 59.1693597671 -2.7001841346 +20146 59.1661874781 -2.7026904476 +20147 59.1628996572 -2.7045478046 +20148 59.1595311842 -2.7057366901 +20149 59.156117784 -2.7062446936 +20150 59.1526956474 -2.7060666323 +20151 59.1493010472 -2.7052045979 +20152 59.1459699536 -2.7036679261 +20153 59.1427376534 -2.7014730884 +20154 59.1396383774 -2.6986435108 +20155 59.1367049386 -2.6952093178 +20156 59.1339683859 -2.6912070085 +20157 59.1314576774 -2.686679065 +20158 59.1291993752 -2.6816734998 +20159 59.1272173661 -2.6762433467 +20160 59.1255326105 -2.6704460993 +20161 59.1241629228 -2.6643431045 +20162 59.1231227835 -2.6579989168 +20163 59.1224231884 -2.6514806197 +20164 59.1220715323 -2.6448571217 +20165 59.1220715323 -2.6381984339 +20166 59.1224231884 -2.6315749359 +20167 59.1231227835 -2.6250566388 +20168 59.1241629228 -2.618712451 +20169 59.1255326105 -2.6126094562 +20170 59.1272173661 -2.6068122088 +20171 59.1291993752 -2.6013820557 +20172 59.1314576774 -2.5963764906 +20173 59.1339683859 -2.591848547 +20174 59.1367049386 -2.5878462377 +20175 59.1396383774 -2.5844120448 +20176 59.1427376534 -2.5815824671 +20177 59.1459699536 -2.5793876295 +20178 59.1493010472 -2.5778509576 +20179 59.1526956474 -2.5769889233 +20180 59.156117784 -2.576810862 +20181 59.1595311842 -2.5773188654 +20182 59.1628996572 -2.578507751 +20183 59.1661874781 -2.5803651079 +20184 59.1693597671 -2.5828714209 +20185 59.1723828607 -2.5860002694 +20186 59.1752246701 -2.5897186017 +20187 59.177855023 -2.5939870801 +20188 59.1802459854 -2.5987604949 +20189 59.1823721602 -2.6039882418 +20190 59.1842109585 -2.6096148588 +20191 59.1857428411 -2.6155806155 +20192 59.1869515277 -2.6218221505 +20193 59.1878241714 -2.6282731481 +20194 59.1883514961 -2.6348650476 +20195 59.1885278961 -2.6415277778 +20196 59.2834190741 -2.575 +20197 59.2832426761 -2.5816812603 +20198 59.2827153572 -2.5882914921 +20199 59.2818427233 -2.5947604287 +20200 59.2806340502 -2.601019318 +20201 59.2791021852 -2.6070016592 +20202 59.2772634082 -2.6126439145 +20203 59.2751372585 -2.6178861871 +20204 59.272746325 -2.6226728607 +20205 59.2701160047 -2.6269531904 +20206 59.2672742313 -2.6306818411 +20207 59.2642511769 -2.6338193664 +20208 59.2610789301 -2.6363326231 +20209 59.2577911543 -2.6381951183 +20210 59.2544227286 -2.6393872831 +20211 59.2510093776 -2.6398966734 +20212 59.2475872917 -2.6397180932 +20213 59.244192743 -2.638853641 +20214 59.2408617011 -2.6373126792 +20215 59.2376294523 -2.6351117263 +20216 59.2345302267 -2.6322742739 +20217 59.2315968366 -2.628830531 +20218 59.2288603301 -2.6248170985 +20219 59.2263496648 -2.6202765767 +20220 59.224091402 -2.6152571117 +20221 59.2221094279 -2.6098118844 +20222 59.2204247025 -2.6039985477 +20223 59.2190550394 -2.5978786183 +20224 59.2180149191 -2.5915168294 +20225 59.2173153368 -2.58498045 +20226 59.2169636871 -2.578338579 +20227 59.2169636871 -2.571661421 +20228 59.2173153368 -2.56501955 +20229 59.2180149191 -2.5584831706 +20230 59.2190550394 -2.5521213817 +20231 59.2204247025 -2.5460014523 +20232 59.2221094279 -2.5401881156 +20233 59.224091402 -2.5347428883 +20234 59.2263496648 -2.5297234233 +20235 59.2288603301 -2.5251829015 +20236 59.2315968366 -2.521169469 +20237 59.2345302267 -2.5177257261 +20238 59.2376294523 -2.5148882737 +20239 59.2408617011 -2.5126873208 +20240 59.244192743 -2.511146359 +20241 59.2475872917 -2.5102819068 +20242 59.2510093776 -2.5101033266 +20243 59.2544227286 -2.5106127169 +20244 59.2577911543 -2.5118048817 +20245 59.2610789301 -2.5136673769 +20246 59.2642511769 -2.5161806336 +20247 59.2672742313 -2.5193181589 +20248 59.2701160047 -2.5230468096 +20249 59.272746325 -2.5273271393 +20250 59.2751372585 -2.5321138129 +20251 59.2772634082 -2.5373560855 +20252 59.2791021852 -2.5429983408 +20253 59.2806340502 -2.548980682 +20254 59.2818427233 -2.5552395713 +20255 59.2827153572 -2.5617085079 +20256 59.2832426761 -2.5683187397 +20257 59.2834190741 -2.575 +20258 59.4008184708 -2.4346972222 +20259 59.4006420752 -2.4414015769 +20260 59.4001147635 -2.4480346567 +20261 59.3992421415 -2.454525951 +20262 59.3980334853 -2.4608064692 +20263 59.3965016417 -2.4668094801 +20264 59.3946628911 -2.4724712256 +20265 59.3925367724 -2.4777316019 +20266 59.3901458745 -2.4825348001 +20267 59.3875155943 -2.4868299002 +20268 59.3846738652 -2.4905714109 +20269 59.3816508592 -2.4937197499 +20270 59.3784786646 -2.4962416607 +20271 59.3751909442 -2.4981105595 +20272 59.3718225769 -2.4993068112 +20273 59.3684092867 -2.4998179299 +20274 59.3649872634 -2.4996387027 +20275 59.3615927783 -2.4987712369 +20276 59.3582618004 -2.4972249285 +20277 59.3550296151 -2.4950163539 +20278 59.3519304518 -2.492169087 +20279 59.3489971217 -2.4887134419 +20280 59.3462606725 -2.4846861463 +20281 59.3437500605 -2.4801299481 +20282 59.3414918463 -2.4750931596 +20283 59.3395099156 -2.4696291451 +20284 59.3378252275 -2.4637957561 +20285 59.336455595 -2.457654721 +20286 59.3354154981 -2.4512709957 +20287 59.3347159315 -2.4447120802 +20288 59.3343642899 -2.438047311 +20289 59.3343642899 -2.4313471335 +20290 59.3347159315 -2.4246823642 +20291 59.3354154981 -2.4181234487 +20292 59.336455595 -2.4117397234 +20293 59.3378252275 -2.4055986884 +20294 59.3395099156 -2.3997652994 +20295 59.3414918463 -2.3943012849 +20296 59.3437500605 -2.3892644964 +20297 59.3462606725 -2.3847082982 +20298 59.3489971217 -2.3806810026 +20299 59.3519304518 -2.3772253575 +20300 59.3550296151 -2.3743780906 +20301 59.3582618004 -2.372169516 +20302 59.3615927783 -2.3706232075 +20303 59.3649872634 -2.3697557417 +20304 59.3684092867 -2.3695765146 +20305 59.3718225769 -2.3700876332 +20306 59.3751909442 -2.3712838849 +20307 59.3784786646 -2.3731527837 +20308 59.3816508592 -2.3756746945 +20309 59.3846738652 -2.3788230336 +20310 59.3875155943 -2.3825645443 +20311 59.3901458745 -2.3868596444 +20312 59.3925367724 -2.3916628426 +20313 59.3946628911 -2.3969232188 +20314 59.3965016417 -2.4025849643 +20315 59.3980334853 -2.4085879752 +20316 59.3992421415 -2.4148684935 +20317 59.4001147635 -2.4213597877 +20318 59.4006420752 -2.4279928675 +20319 59.4008184708 -2.4346972222 +20320 59.5679759474 -1.6285111111 +20321 59.5677995552 -1.6352486751 +20322 59.5672722537 -1.6419146096 +20323 59.5663996487 -1.6484380536 +20324 59.5651910162 -1.6547496737 +20325 59.5636592032 -1.660782407 +20326 59.5618204898 -1.6664721789 +20327 59.559694415 -1.6717585875 +20328 59.5573035675 -1.6765855474 +20329 59.554673344 -1.6809018868 +20330 59.5518316778 -1.6846618895 +20331 59.5488087405 -1.6878257782 +20332 59.5456366198 -1.6903601329 +20333 59.5423489782 -1.6922382397 +20334 59.5389806938 -1.6934403679 +20335 59.5355674899 -1.6939539715 +20336 59.5321455553 -1.6937738138 +20337 59.5287511606 -1.6929020143 +20338 59.5254202735 -1.6913480172 +20339 59.5221881786 -1.6891284828 +20340 59.5190891037 -1.6862671028 +20341 59.5161558591 -1.6827943426 +20342 59.5134194912 -1.6787471124 +20343 59.510908955 -1.674168372 +20344 59.5086508102 -1.669106673 +20345 59.5066689411 -1.6636156433 +20346 59.504984306 -1.6577534201 +20347 59.503614717 -1.6515820362 +20348 59.5025746534 -1.6451667673 +20349 59.5018751093 -1.6385754462 +20350 59.501523479 -1.6318777503 +20351 59.501523479 -1.6251444719 +20352 59.5018751093 -1.6184467761 +20353 59.5025746534 -1.6118554549 +20354 59.503614717 -1.605440186 +20355 59.504984306 -1.5992688021 +20356 59.5066689411 -1.5934065789 +20357 59.5086508102 -1.5879155492 +20358 59.510908955 -1.5828538502 +20359 59.5134194912 -1.5782751099 +20360 59.5161558591 -1.5742278797 +20361 59.5190891037 -1.5707551194 +20362 59.5221881786 -1.5678937394 +20363 59.5254202735 -1.565674205 +20364 59.5287511606 -1.5641202079 +20365 59.5321455553 -1.5632484084 +20366 59.5355674899 -1.5630682507 +20367 59.5389806938 -1.5635818543 +20368 59.5423489782 -1.5647839825 +20369 59.5456366198 -1.5666620893 +20370 59.5488087405 -1.569196444 +20371 59.5518316778 -1.5723603328 +20372 59.554673344 -1.5761203355 +20373 59.5573035675 -1.5804366748 +20374 59.559694415 -1.5852636348 +20375 59.5618204898 -1.5905500433 +20376 59.5636592032 -1.5962398152 +20377 59.5651910162 -1.6022725485 +20378 59.5663996487 -1.6085841686 +20379 59.5672722537 -1.6151076126 +20380 59.5677995552 -1.6217735472 +20381 59.5679759474 -1.6285111111 +20382 59.9147235403 -1.2938289167 +20383 59.914547155 -1.3006366179 +20384 59.9140198744 -1.3073719411 +20385 59.9131473042 -1.3139632846 +20386 59.9119387204 -1.3203405909 +20387 59.91040697 -1.3264360969 +20388 59.908568333 -1.3321850596 +20389 59.9064423484 -1.3375264472 +20390 59.9040516045 -1.3424035907 +20391 59.9014214977 -1.346764786 +20392 59.8985799609 -1.3505638424 +20393 59.8955571648 -1.3537605706 +20394 59.8923851965 -1.3563212053 +20395 59.8890977171 -1.3582187579 +20396 59.8857296036 -1.3594332958 +20397 59.8823165777 -1.3599521463 +20398 59.8788948264 -1.3597700222 +20399 59.8755006183 -1.3588890691 +20400 59.8721699191 -1.3573188329 +20401 59.8689380107 -1.3550761509 +20402 59.8658391189 -1.3521849641 +20403 59.8629060512 -1.3486760571 +20404 59.8601698514 -1.3445867258 +20405 59.8576594723 -1.3399603776 +20406 59.855401471 -1.3348460691 +20407 59.8534197296 -1.3292979853 +20408 59.8517352043 -1.3233748663 +20409 59.8503657054 -1.317139388 +20410 59.8493257108 -1.310657502 +20411 59.8486262133 -1.3039977428 +20412 59.8482746066 -1.2972305088 +20413 59.8482746066 -1.2904273245 +20414 59.8486262133 -1.2836600906 +20415 59.8493257108 -1.2770003314 +20416 59.8503657054 -1.2705184453 +20417 59.8517352043 -1.264282967 +20418 59.8534197296 -1.258359848 +20419 59.855401471 -1.2528117642 +20420 59.8576594723 -1.2476974557 +20421 59.8601698514 -1.2430711075 +20422 59.8629060512 -1.2389817762 +20423 59.8658391189 -1.2354728692 +20424 59.8689380107 -1.2325816824 +20425 59.8721699191 -1.2303390004 +20426 59.8755006183 -1.2287687643 +20427 59.8788948264 -1.2278878111 +20428 59.8823165777 -1.227705687 +20429 59.8857296036 -1.2282245375 +20430 59.8890977171 -1.2294390754 +20431 59.8923851965 -1.231336628 +20432 59.8955571648 -1.2338972627 +20433 59.8985799609 -1.237093991 +20434 59.9014214977 -1.2408930474 +20435 59.9040516045 -1.2452542426 +20436 59.9064423484 -1.2501313861 +20437 59.908568333 -1.2554727738 +20438 59.91040697 -1.2612217364 +20439 59.9119387204 -1.2673172424 +20440 59.9131473042 -1.2736945487 +20441 59.9140198744 -1.2802858923 +20442 59.914547155 -1.2870212155 +20443 59.9147235403 -1.2938289167 +20444 59.8444108056 -1.3568085833 +20445 59.8540180556 -1.3311036389 +20446 59.8558562601 -1.3359630795 +20447 59.8579111898 -1.3404666687 +20448 59.8601654722 -1.3445763333 +20449 59.8516208056 -1.3674341667 +20450 59.8444108056 -1.3568085833 +20451 59.9079886667 -1.2162301667 +20452 59.8997096111 -1.2384997778 +20453 59.897077012 -1.2354006971 +20454 59.8943124159 -1.2327967446 +20455 59.89143925 -1.2307098611 +20456 59.9007787222 -1.2055865833 +20457 59.9079886667 -1.2162301667 +20458 59.87130875 -1.3929947222 +20459 59.8733186944 -1.3579365 +20460 59.8762570415 -1.3591408487 +20461 59.8792380001 -1.359813575 +20462 59.8822373056 -1.3599490556 +20463 59.8802280556 -1.3949956111 +20464 59.87130875 -1.3929947222 +20465 59.8916009167 -1.19437 +20466 59.8896215833 -1.2296873611 +20467 59.8866824629 -1.2284900505 +20468 59.8837010623 -1.2278249785 +20469 59.8807016667 -1.2276974167 +20470 59.8826816389 -1.1923684444 +20471 59.8916009167 -1.19437 +20472 59.9138691667 -1.3589489444 +20473 59.9034362778 -1.3434973056 +20474 59.9056034287 -1.3393430101 +20475 59.9075729269 -1.3348151617 +20476 59.9093286111 -1.3299508611 +20477 59.9192197778 -1.34459625 +20478 59.9138691667 -1.3589489444 +20479 59.8395753611 -1.226986 +20480 59.8560408056 -1.2512414722 +20481 59.8542101142 -1.2559873152 +20482 59.8526025447 -1.2610422146 +20483 59.8512312222 -1.2663648333 +20484 59.8342246667 -1.2413044167 +20485 59.8395753611 -1.226986 +20486 59.3832852275 -2.949875 +20487 59.3831088315 -2.9565758937 +20488 59.3825815187 -2.9632055494 +20489 59.381708895 -2.969693493 +20490 59.3805002362 -2.9759707698 +20491 59.3789683895 -2.9819706831 +20492 59.3771296349 -2.9876295077 +20493 59.3750035117 -2.9928871709 +20494 59.3726126084 -2.9976878926 +20495 59.3699823222 -3.0019807792 +20496 59.3671405865 -3.0057203627 +20497 59.3641175733 -3.0088670811 +20498 59.3609453709 -3.011387695 +20499 59.3576576423 -3.0132556341 +20500 59.3542892663 -3.0144512734 +20501 59.350875967 -3.014962133 +20502 59.3474539343 -3.0147830028 +20503 59.3440594397 -3.0139159887 +20504 59.3407284522 -3.0123704815 +20505 59.3374962575 -3.0101630491 +20506 59.3343970849 -3.0073172531 +20507 59.3314637459 -3.0038633917 +20508 59.3287272881 -2.9998381737 +20509 59.3262166681 -2.9952843248 +20510 59.3239584467 -2.9902501325 +20511 59.3219765095 -2.9847889335 +20512 59.3202918158 -2.9789585496 +20513 59.3189221788 -2.9728206775 +20514 59.3178820784 -2.9664402396 +20515 59.3171825094 -2.9598847015 +20516 59.3168308666 -2.9532233639 +20517 59.3168308666 -2.9465266361 +20518 59.3171825094 -2.9398652985 +20519 59.3178820784 -2.9333097604 +20520 59.3189221788 -2.9269293225 +20521 59.3202918158 -2.9207914504 +20522 59.3219765095 -2.9149610665 +20523 59.3239584467 -2.9094998675 +20524 59.3262166681 -2.9044656752 +20525 59.3287272881 -2.8999118263 +20526 59.3314637459 -2.8958866083 +20527 59.3343970849 -2.8924327469 +20528 59.3374962575 -2.8895869509 +20529 59.3407284522 -2.8873795185 +20530 59.3440594397 -2.8858340113 +20531 59.3474539343 -2.8849669972 +20532 59.350875967 -2.884787867 +20533 59.3542892663 -2.8852987266 +20534 59.3576576423 -2.8864943659 +20535 59.3609453709 -2.888362305 +20536 59.3641175733 -2.8908829189 +20537 59.3671405865 -2.8940296373 +20538 59.3699823222 -2.8977692208 +20539 59.3726126084 -2.9020621074 +20540 59.3750035117 -2.9068628291 +20541 59.3771296349 -2.9121204923 +20542 59.3789683895 -2.9177793169 +20543 59.3805002362 -2.9237792302 +20544 59.381708895 -2.930056507 +20545 59.3825815187 -2.9365444506 +20546 59.3831088315 -2.9431741063 +20547 59.3832852275 -2.949875 +20548 59.3841574452 -2.90035 +20549 59.3839810493 -2.9070510658 +20550 59.3834537366 -2.9136808917 +20551 59.3825811129 -2.9201690019 +20552 59.3813724543 -2.9264464399 +20553 59.3798406077 -2.9324465072 +20554 59.3780018533 -2.938105477 +20555 59.3758757303 -2.943363275 +20556 59.3734848273 -2.9481641199 +20557 59.3708545414 -2.9524571166 +20558 59.368012806 -2.9561967958 +20559 59.3649897932 -2.9593435949 +20560 59.3618175912 -2.9618642732 +20561 59.3585298629 -2.9637322601 +20562 59.3551614874 -2.9649279298 +20563 59.3517481885 -2.9654388023 +20564 59.3483261563 -2.9652596673 +20565 59.3449316622 -2.9643926307 +20566 59.3416006752 -2.9628470836 +20567 59.338368481 -2.9606395945 +20568 59.3352693088 -2.9577937253 +20569 59.3323359702 -2.9543397752 +20570 59.3295995128 -2.9503144539 +20571 59.3270888933 -2.9457604882 +20572 59.3248306723 -2.9407261668 +20573 59.3228487353 -2.9352648279 +20574 59.3211640419 -2.9294342945 +20575 59.3197944051 -2.9232962652 +20576 59.3187543049 -2.9169156639 +20577 59.3180547361 -2.9103599579 +20578 59.3177030933 -2.9036984496 +20579 59.3177030933 -2.8970015504 +20580 59.3180547361 -2.8903400421 +20581 59.3187543049 -2.8837843361 +20582 59.3197944051 -2.8774037348 +20583 59.3211640419 -2.8712657055 +20584 59.3228487353 -2.8654351721 +20585 59.3248306723 -2.8599738332 +20586 59.3270888933 -2.8549395118 +20587 59.3295995128 -2.8503855461 +20588 59.3323359702 -2.8463602248 +20589 59.3352693088 -2.8429062747 +20590 59.338368481 -2.8400604055 +20591 59.3416006752 -2.8378529164 +20592 59.3449316622 -2.8363073693 +20593 59.3483261563 -2.8354403327 +20594 59.3517481885 -2.8352611977 +20595 59.3551614874 -2.8357720702 +20596 59.3585298629 -2.8369677399 +20597 59.3618175912 -2.8388357268 +20598 59.3649897932 -2.8413564051 +20599 59.368012806 -2.8445032042 +20600 59.3708545414 -2.8482428834 +20601 59.3734848273 -2.8525358801 +20602 59.3758757303 -2.857336725 +20603 59.3780018533 -2.862594523 +20604 59.3798406077 -2.8682534928 +20605 59.3813724543 -2.8742535601 +20606 59.3825811129 -2.8805309981 +20607 59.3834537366 -2.8870191083 +20608 59.3839810493 -2.8936489342 +20609 59.3841574452 -2.90035 +EOF diff --git a/Trav_SalMan.py b/Trav_SalMan.py new file mode 100644 index 0000000000..1a6ea6429e --- /dev/null +++ b/Trav_SalMan.py @@ -0,0 +1,195 @@ +import copy +import matplotlib.pyplot as plt +import networkx as nx +import numpy as np +import numpy.random as rnd +import tsplib95 +import tsplib95.distances as distances + +from alns import ALNS +from alns.accept import HillClimbing +from alns.select import RouletteWheel +from alns.stop import MaxRuntime + +SEED = 7654 +DATA = tsplib95.load('/home/dell/ALNS/examples/data/xqf131.tsp') +CITIES = list(DATA.node_coords.keys()) + +COORDS = DATA.node_coords.values() +DIST = np.empty((len(COORDS) + 1, len(COORDS) + 1)) + +for row, coord1 in enumerate(COORDS, 1): + for col, coord2 in enumerate(COORDS, 1): + DIST[row, col] = distances.euclidean(coord1, coord2) + +SOLUTION = tsplib95.load('/home/dell/ALNS/examples/data/xqf131.opt.tour') +OPTIMAL = DATA.trace_tours(SOLUTION.tours)[0] + +print(f"Total optimal tour length is {OPTIMAL}.") + + +def draw_graph(graph, only_nodes=False, ax=None, title=None): + """ + Helper method for drawing TSP (tour) graphs. + """ + if ax is None: + fig, ax = plt.subplots(figsize=(12, 6)) + + if only_nodes: + nx.draw_networkx_nodes(graph, DATA.node_coords, node_size=25, ax=ax) + else: + nx.draw_networkx(graph, DATA.node_coords, node_size=25, with_labels=False, ax=ax) + + if title: + ax.set_title(title) + + +class TspState: + """ + Solution class for the TSP problem. It has two data members, nodes, and edges. + nodes is a list of IDs. The edges data member, then, is a mapping from each node + to their only outgoing node. + """ + + def __init__(self, nodes, edges): + self.nodes = nodes + self.edges = edges + + def objective(self): + """ + The objective function is simply the sum of all individual edge lengths, + using the rounded Euclidean norm. + """ + return sum(DIST[node, self.edges[node]] for node in self.nodes) + + def to_graph(self): + """ + NetworkX helper method. + """ + graph = nx.Graph() + + for node in self.nodes: + graph.add_node(node, pos=DATA.node_coords[node]) + + for node_from, node_to in self.edges.items(): + graph.add_edge(node_from, node_to) + + return graph + + +DEGREE_OF_DESTRUCTION = 0.1 + + +def edges_to_remove(state): + return int(len(state.edges) * DEGREE_OF_DESTRUCTION) + + +def worst_removal(current, rnd_state): + """ + Worst removal iteratively removes the 'worst' edges, that is, + those edges that have the largest distance. + """ + destroyed = copy.deepcopy(current) + + worst_edges = sorted(destroyed.nodes, + key=lambda node: DIST[node, destroyed.edges[node]]) + + for idx in range(edges_to_remove(current)): + del destroyed.edges[worst_edges[-(idx + 1)]] + + return destroyed + + +def path_removal(current, rnd_state): + """ + Removes an entire consecutive sub-path, that is, a series of + contiguous edges. + """ + destroyed = copy.deepcopy(current) + + node_idx = rnd_state.choice(len(destroyed.nodes)) + node = destroyed.nodes[node_idx] + + for _ in range(edges_to_remove(current)): + node = destroyed.edges.pop(node) + + return destroyed + + +def random_removal(current, rnd_state): + """ + Random removal iteratively removes random edges. + """ + destroyed = copy.deepcopy(current) + + for idx in rnd_state.choice(len(destroyed.nodes), + edges_to_remove(current), + replace=False): + del destroyed.edges[destroyed.nodes[idx]] + + return destroyed + + +def would_form_subcycle(from_node, to_node, state): + """ + Ensures the proposed solution would not result in a cycle smaller + than the entire set of nodes. + """ + for step in range(1, len(state.nodes)): + if to_node not in state.edges: + return False + + to_node = state.edges[to_node] + + if from_node == to_node and step != len(state.nodes) - 1: + return True + + return False + + +def greedy_repair(current, rnd_state): + """ + Greedily repairs a tour, stitching up nodes that are not departed + with those not visited. + """ + visited = set(current.edges.values()) + + shuffled_idcs = rnd_state.permutation(len(current.nodes)) + nodes = [current.nodes[idx] for idx in shuffled_idcs] + + while len(current.edges) != len(current.nodes): + node = next(node for node in nodes + if node not in current.edges) + + unvisited = {other for other in current.nodes + if other != node + if other not in visited + if not would_form_subcycle(node, other, current)} + + nearest = min(unvisited, + key=lambda other: DIST[node, other]) + + current.edges[node] = nearest + visited.add(nearest) + + return current + + +# Initialize random state and initial solution +random_state = rnd.RandomState(SEED) +state = TspState(CITIES, {}) + +# Initial greedy repair solution +init_sol = greedy_repair(state, random_state) +print(f"Initial solution objective is {init_sol.objective()}.") + +# Create subplots +fig, (ax1, ax2) = plt.subplots(1, 2, figsize=(16, 6)) + +# Plot both graphs +draw_graph(init_sol.to_graph(), ax=ax1, title="Initial Solution") +draw_graph(DATA.get_graph(), only_nodes=True, ax=ax2, title="Original Graph with Nodes Only") + +plt.tight_layout() +plt.show() + diff --git a/Trav_SalMan1.py b/Trav_SalMan1.py new file mode 100644 index 0000000000..88c0f16344 --- /dev/null +++ b/Trav_SalMan1.py @@ -0,0 +1,160 @@ +import copy +import matplotlib.pyplot as plt +import networkx as nx +import numpy as np +import numpy.random as rnd +import tsplib95 +import tsplib95.distances as distances + +from alns import ALNS +from alns.accept import HillClimbing +from alns.select import RouletteWheel +from alns.stop import MaxRuntime + +# Set seed for reproducibility +SEED = 7654 + +# Load TSP data +DATA = tsplib95.load('/home/dell/ALNS/examples/data/xqf131.tsp') +CITIES = list(DATA.node_coords.keys()) + +# Precompute distance matrix +COORDS = DATA.node_coords.values() +DIST = np.empty((len(COORDS) + 1, len(COORDS) + 1)) +for row, coord1 in enumerate(COORDS, 1): + for col, coord2 in enumerate(COORDS, 1): + DIST[row, col] = distances.euclidean(coord1, coord2) + +# Load optimal solution for comparison +SOLUTION = tsplib95.load('/home/dell/ALNS/examples/data/xqf131.opt.tour') +OPTIMAL = DATA.trace_tours(SOLUTION.tours)[0] +print(f"Total optimal tour length is {OPTIMAL}.") + +# Helper function to draw TSP graphs +def draw_graph(graph, only_nodes=False, ax=None): + if ax is None: + fig, ax = plt.subplots(figsize=(12, 6)) + + pos = DATA.node_coords + if only_nodes: + nodes_to_draw = [node for node in graph.nodes if node in pos] + nx.draw_networkx_nodes(graph, pos, nodelist=nodes_to_draw, node_size=25, ax=ax) + else: + nx.draw_networkx(graph, pos, with_labels=False, ax=ax) + + +# Solution class for TSP problem +class TspState: + def __init__(self, nodes, edges): + self.nodes = nodes + self.edges = edges + + def objective(self): + return sum(DIST[node, self.edges[node]] for node in self.nodes) + + def to_graph(self): + graph = nx.Graph() + for node in self.nodes: + graph.add_node(node, pos=DATA.node_coords[node]) + for node_from, node_to in self.edges.items(): + graph.add_edge(node_from, node_to) + return graph + +# Operators for ALNS +DEGREE_OF_DESTRUCTION = 0.1 + +def edges_to_remove(state): + return int(len(state.edges) * DEGREE_OF_DESTRUCTION) + +def worst_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + worst_edges = sorted(destroyed.nodes, key=lambda node: DIST[node, destroyed.edges[node]]) + for idx in range(edges_to_remove(current)): + del destroyed.edges[worst_edges[-(idx + 1)]] + return destroyed + +def path_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + node_idx = rnd_state.choice(len(destroyed.nodes)) + node = destroyed.nodes[node_idx] + for _ in range(edges_to_remove(current)): + node = destroyed.edges.pop(node) + return destroyed + +def random_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + for idx in rnd_state.choice(len(destroyed.nodes), edges_to_remove(current), replace=False): + del destroyed.edges[destroyed.nodes[idx]] + return destroyed + +def would_form_subcycle(from_node, to_node, state): + for step in range(1, len(state.nodes)): + if to_node not in state.edges: + return False + to_node = state.edges[to_node] + if from_node == to_node and step != len(state.nodes) - 1: + return True + return False + +def greedy_repair(current, rnd_state): + visited = set(current.edges.values()) + shuffled_idcs = rnd_state.permutation(len(current.nodes)) + nodes = [current.nodes[idx] for idx in shuffled_idcs] + while len(current.edges) != len(current.nodes): + node = next(node for node in nodes if node not in current.edges) + unvisited = {other for other in current.nodes if other != node + if other not in visited + if not would_form_subcycle(node, other, current)} + nearest = min(unvisited, key=lambda other: DIST[node, other]) + current.edges[node] = nearest + visited.add(nearest) + return current + +# Initialize random state +random_state = rnd.RandomState(SEED) +state = TspState(CITIES, {}) + +# Initial solution using greedy repair +init_sol = greedy_repair(state, random_state) +print(f"Initial solution objective is {init_sol.objective()}.") + +# ALNS initialization and parameters +alns = ALNS(random_state) +alns.add_destroy_operator(random_removal) +alns.add_destroy_operator(path_removal) +alns.add_destroy_operator(worst_removal) +alns.add_repair_operator(greedy_repair) + +# ALNS parameters and execution +select = RouletteWheel([3, 2, 1, 0.5], 0.8, 3, 1) +accept = HillClimbing() +stop = MaxRuntime(60) + +# Run ALNS on the initial solution +result = alns.iterate(init_sol, select, accept, stop) +solution = result.best_state +objective = solution.objective() +pct_diff = 100 * (objective - OPTIMAL) / OPTIMAL + +print(f"Best heuristic objective is {objective}.") +print(f"This is {pct_diff:.1f}% worse than the optimal solution, which is {OPTIMAL}.") + +# Plotting all graphs side by side +fig, axs = plt.subplots(1, 3, figsize=(18, 6)) + +# Plot the initial solution +draw_graph(init_sol.to_graph(), ax=axs[0]) +axs[0].set_title('Initial Solution') + +# Plot the ALNS objectives +result.plot_objectives(ax=axs[1], lw=2) +axs[1].set_title('ALNS Objectives') + +# Plot the optimal solution +draw_graph(SOLUTION.get_graph(), only_nodes=True, ax=axs[2]) +axs[2].set_title('Optimal Solution') + +# Adjust layout and display the plots +plt.tight_layout() +plt.show() + diff --git a/Trav_SalMan1_hospitals.py b/Trav_SalMan1_hospitals.py new file mode 100644 index 0000000000..74ff0bc153 --- /dev/null +++ b/Trav_SalMan1_hospitals.py @@ -0,0 +1,231 @@ +import copy +import matplotlib.pyplot as plt +import networkx as nx +import numpy as np +import numpy.random as rnd +import tsplib95 +import tsplib95.distances as distances +from math import radians, sin, cos, sqrt, atan2 + +from alns import ALNS +from alns.accept import HillClimbing +from alns.select import RouletteWheel +from alns.stop import MaxRuntime + +# Set seed for reproducibility +SEED = 7654 + +# Load TSP data +DATA = tsplib95.load('/home/dell/ALNS/Destinations.tsp') +CITIES = list(DATA.node_coords.keys()) + +# Load fences data +def load_fences(filename): + with open(filename, 'r') as file: + lines = file.readlines() + fences = [] + read_fences = False + for line in lines: + if line.strip() == "EDGE_COORD_SECTION": + read_fences = True + continue + if read_fences: + if line.strip() == "EOF": + break + parts = list(map(float, line.strip().split())) + if len(parts) == 4: + fences.append(parts) + return fences + +FENCES = load_fences('/home/dell/ALNS/Fences.tsp') + +def intersects_fence(coord1, coord2, fence): + # Function to check if a line segment from coord1 to coord2 intersects a fence + x1, y1 = coord1 + x2, y2 = coord2 + fx1, fy1, fx2, fy2 = fence + + def ccw(A, B, C): + return (C[1] - A[1]) * (B[0] - A[0]) > (B[1] - A[1]) * (C[0] - A[0]) + + return ccw((x1, y1), (fx1, fy1), (fx2, fy2)) != ccw((x2, y2), (fx1, fy1), (fx2, fy2)) and \ + ccw((x1, y1), (x2, y2), (fx1, fy1)) != ccw((x1, y1), (x2, y2), (fx2, fy2)) + +def path_valid(coord1, coord2): + return not any(intersects_fence(coord1, coord2, fence) for fence in FENCES) + +def haversine_distance(coord1, coord2): + # Convert latitude and longitude from degrees to radians + lat1, lon1 = map(radians, coord1) + lat2, lon2 = map(radians, coord2) + + # Haversine formula + dlat = lat2 - lat1 + dlon = lon2 - lon1 + a = sin(dlat / 2)**2 + cos(lat1) * cos(lat2) * sin(dlon / 2)**2 + c = 2 * atan2(sqrt(a), sqrt(1 - a)) + radius_of_earth_km = 6371.0 # Radius of the Earth in kilometers + distance = radius_of_earth_km * c + + return distance + +# Precompute distance matrix with fences +COORDS = list(DATA.node_coords.values()) +DIST = np.empty((len(COORDS) + 1, len(COORDS) + 1)) +for row, coord1 in enumerate(COORDS, 1): + for col, coord2 in enumerate(COORDS, 1): + if row == col: + DIST[row, col] = 0 + else: + dist = haversine_distance(coord1, coord2) + if not path_valid(coord1, coord2): + dist = np.inf # Use a very large number to indicate an impassable path + DIST[row, col] = dist + +# Helper function to draw TSP graphs +def draw_graph(graph, only_nodes=False, ax=None): + if ax is None: + fig, ax = plt.subplots(figsize=(12, 6)) + + pos = DATA.node_coords + if only_nodes: + nodes_to_draw = [node for node in graph.nodes if node in pos] + nx.draw_networkx_nodes(graph, pos, nodelist=nodes_to_draw, node_size=25, ax=ax) + else: + nx.draw_networkx(graph, pos, with_labels=False, ax=ax) + + # Draw fences + for fence in FENCES: + x_values = [fence[0], fence[2]] + y_values = [fence[1], fence[3]] + ax.plot(x_values, y_values, 'r-') + +# Solution class for TSP problem +class TspState: + def __init__(self, nodes, edges): + self.nodes = nodes + self.edges = edges + + def objective(self): + return sum(DIST[node, self.edges[node]] for node in self.nodes) + + def to_graph(self): + graph = nx.Graph() + for node in self.nodes: + graph.add_node(node, pos=DATA.node_coords[node]) + for node_from, node_to in self.edges.items(): + graph.add_edge(node_from, node_to) + return graph + +# Operators for ALNS +DEGREE_OF_DESTRUCTION = 0.1 + +def edges_to_remove(state): + return int(len(state.edges) * DEGREE_OF_DESTRUCTION) + +def worst_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + worst_edges = sorted(destroyed.nodes, key=lambda node: DIST[node, destroyed.edges[node]]) + for idx in range(edges_to_remove(current)): + del destroyed.edges[worst_edges[-(idx + 1)]] + return destroyed + +def path_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + node_idx = rnd_state.choice(len(destroyed.nodes)) + node = destroyed.nodes[node_idx] + for _ in range(edges_to_remove(current)): + node = destroyed.edges.pop(node) + return destroyed + +def random_removal(current, rnd_state): + destroyed = copy.deepcopy(current) + for idx in rnd_state.choice(len(destroyed.nodes), edges_to_remove(current), replace=False): + del destroyed.edges[destroyed.nodes[idx]] + return destroyed + +def would_form_subcycle(from_node, to_node, state): + for step in range(1, len(state.nodes)): + if to_node not in state.edges: + return False + to_node = state.edges[to_node] + if from_node == to_node and step != len(state.nodes) - 1: + return True + return False + +def greedy_repair(current, rnd_state): + visited = set(current.edges.values()) + shuffled_idcs = rnd_state.permutation(len(current.nodes)) + nodes = [current.nodes[idx] for idx in shuffled_idcs] + while len(current.edges) != len(current.nodes): + node = next(node for node in nodes if node not in current.edges) + unvisited = {other for other in current.nodes if other != node + if other not in visited + if not would_form_subcycle(node, other, current) + if path_valid(DATA.node_coords[node], DATA.node_coords[other])} + if not unvisited: + # If no valid unvisited nodes remain, we need to backtrack + continue + nearest = min(unvisited, key=lambda other: DIST[node, other]) + current.edges[node] = nearest + visited.add(nearest) + return current + +# Initialize random state +random_state = rnd.RandomState(SEED) +state = TspState(CITIES, {}) + +# Initial solution using greedy repair +init_sol = greedy_repair(state, random_state) +initial_objective = init_sol.objective() +print(f"Initial solution objective (distance): {initial_objective:.2f} km") + +# ALNS initialization and parameters +alns = ALNS(random_state) +alns.add_destroy_operator(random_removal) +alns.add_destroy_operator(path_removal) +alns.add_destroy_operator(worst_removal) +alns.add_repair_operator(greedy_repair) + +# ALNS parameters and execution +select = RouletteWheel([3, 2, 1, 0.5], 0.8, 3, 1) +accept = HillClimbing() +stop = MaxRuntime(600) # Increased runtime for better chances of finding improvements + +# Run ALNS on the initial solution +result = alns.iterate(init_sol, select, accept, stop) +solution = result.best_state +solution_objective = solution.objective() + +print(f"Best solution objective (distance) avoiding fences: {solution_objective:.2f} km") + +# Check if the best solution is different from the initial solution +if initial_objective == solution_objective: + print("ALNS did not find a better solution.") + +# Plotting the initial solution, ALNS objectives, and the best solution +fig, axs = plt.subplots(1, 3, figsize=(24, 8)) + +# Plot the initial solution +draw_graph(init_sol.to_graph(), ax=axs[0]) +axs[0].set_title('Initial Solution') + +# Plot the ALNS objectives +result.plot_objectives(ax=axs[1], lw=2) +axs[1].set_title('ALNS Objectives') + +# Plot the best solution found by ALNS +draw_graph(solution.to_graph(), ax=axs[2]) +axs[2].set_title('Best Solution Found by ALNS') + +# Draw fences on all plots for clarity +for ax in axs: + for fence in FENCES: + x_values = [fence[0], fence[2]] + y_values = [fence[1], fence[3]] + ax.plot(x_values, y_values, 'r-') + +# Adjust layout and display the plots +plt.tight_layout() +plt.show() + From 2443950560bbd0cfd8424662c348d77ff9509e4a Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sat, 6 Jul 2024 23:13:39 +0100 Subject: [PATCH 18/33] Update README.md --- README.md | 9 --------- 1 file changed, 9 deletions(-) diff --git a/README.md b/README.md index 3363e3b6a4..583f9ae7eb 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,3 @@ -header pic - -# PythonRobotics -![GitHub_Action_Linux_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Linux_CI/badge.svg) -![GitHub_Action_MacOS_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/MacOS_CI/badge.svg) -![GitHub_Action_Windows_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Windows_CI/badge.svg) -[![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) -[![codecov](https://codecov.io/gh/AtsushiSakai/PythonRobotics/branch/master/graph/badge.svg)](https://codecov.io/gh/AtsushiSakai/PythonRobotics) - Python codes for robotics algorithm. From 587e8d4fd48474d64f24fc07e2a67a84b5470c53 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 7 Jul 2024 00:16:36 +0100 Subject: [PATCH 19/33] Add files via upload --- Destinations.kml | 426 ++++++++++++++++++++++++++--------------------- Destinations.tsp | 60 +++---- 2 files changed, 262 insertions(+), 224 deletions(-) diff --git a/Destinations.kml b/Destinations.kml index ae166995dc..68e2a9785e 100644 --- a/Destinations.kml +++ b/Destinations.kml @@ -31,7 +31,7 @@ - + - + + + + normal - #__managed_style_14A059B9A031BF14491C + #__managed_style_1DF75EF5A831BF144915 highlight - #__managed_style_071CBFDE2F31BF14491D + #__managed_style_2EFD52E0E431BF144915 - + - + + + + + normal + #__managed_style_14A059B9A031BF14491C + + + highlight + #__managed_style_071CBFDE2F31BF14491D + + + + - + normal - #__managed_style_1DF75EF5A831BF144915 + #__managed_style_154DBAE30C31BF9E7CDA highlight - #__managed_style_2EFD52E0E431BF144915 + #__managed_style_257EED039631BF9E7CDA Destinations 1 - - Vale Drive Primary Care Centre - - -0.1968710123449446 - 51.65064622007617 - 119.0496245502007 - 33.95610494125125 - 51.61511454086038 - 35 - 783.3107969355478 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.1951169862852115,51.6497469421364,106.8249971668427 - - Broomfield Hospital @@ -153,7 +191,7 @@ 962.681589408021 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4661826118043533,51.77432116677244,62.15314977461038 @@ -170,7 +208,7 @@ 7908.249561059058 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.8989016354739056,51.90985612864645,52.129981717103 @@ -187,7 +225,7 @@ 4063.273102276144 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.8950007512019129,51.90631333268821,40.85532839312136 @@ -204,7 +242,7 @@ 4063.273102276144 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.9020700978708827,51.90668078352024,41.05316266193498 @@ -221,7 +259,7 @@ 3513.147033427376 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4847439958367916,51.75341033368938,37.20936407432514 @@ -238,7 +276,7 @@ 3513.147033427376 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4860906915350229,51.75595480607432,30.37470452823173 @@ -255,7 +293,7 @@ 1906.346236672543 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4851154704670301,51.74716663521045,42.72730373314561 @@ -272,9 +310,9 @@ 8924.934771554545 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - 0.1237980769230785,51.70491929118251,115.6421697734014 + 0.1255747078023273,51.70288283015128,115.6421697734014 @@ -289,9 +327,9 @@ 2867.143209121423 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - 0.08539556146978197,51.76952006829818,64.14747173662603 + 0.08565868894554463,51.76912716012718,64.14747173662603 @@ -306,9 +344,9 @@ 2867.143209121423 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - 0.0868200246143358,51.77176739550571,69.79413382101708 + 0.08681342944926174,51.77177470864583,69.79413382101708 @@ -323,7 +361,7 @@ 3163.337353592506 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.1129865782056449,51.75607366423915,73.36016156645285 @@ -340,9 +378,9 @@ 5790.285723345587 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - 0.1356597399818305,51.80818175439255,68.28605103152285 + 0.1357804869768531,51.80828291123409,68.28605103152285 @@ -362,91 +400,6 @@ 0.6877328222924616,51.55385927682786,40.11469741632487 - - St Albans City Hospital - - -0.3457139310618307 - 51.74319846245394 - 91.24766614316273 - 53.11981616282007 - 60.0613137551813 - 35 - 15419.13049176335 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.3435461023351755,51.76043771309943,110.8324392548333 - - - - Hemel Hempsteam Hospital - - -0.4695075770543722 - 51.75069927539609 - 108.933477195889 - 52.91641952113871 - 59.94724979383651 - 35 - 764.7829484937392 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.4691092344696746,51.7516592203038,124.3043795309861 - - - - Stoke Mandeville Hospital - - -0.7978240106556145 - 51.79912316487393 - 86.01612159447117 - 52.82577528013368 - 51.35198755734502 - 35 - 1424.284711338842 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.8061987654715064,51.81044035125617,88.5627270743543 - - - - Stoke Mandeville Hospital Emergency - - -0.7978240106556145 - 51.79912316487393 - 86.01612159447117 - 52.82577528013368 - 51.35198755734502 - 35 - 1424.284711338842 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.8014090401785613,51.79736510287374,90.28124226004431 - - - - Waddesdon Wing Maternity Outpatients Antenatal - - -0.8021384379958951 - 51.79719545416784 - 90.92761652804441 - 52.81887036614162 - 51.34717542765949 - 35 - 739.049740673363 - absolute - - #__managed_style_06A96EF91C31BF144915 - - -0.8000927812905456,51.79724865426316,92.9616022829897 - - Phoenix Hospital Chelmsford @@ -459,7 +412,7 @@ 7175.670542574953 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.5035843063186717,51.70695925794588,36.53239001018486 @@ -476,7 +429,7 @@ 1195.337775519001 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4710096422132502,51.73092405457083,35.83657572852461 @@ -493,7 +446,7 @@ 1147.535923757823 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.4663354223901122,51.72999144599143,31.24564959711314 @@ -510,7 +463,7 @@ 1537.691036219039 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.456043285327947,51.72642076891589,48.45157475308184 @@ -527,111 +480,196 @@ 2694.211246461491 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA 0.42651098901098,51.73261225563316,35.54494197837538 - - Barnet Hospital + + Cheshunt Community Hospital - -0.2142299080354926 - 51.65015280865894 - 116.3103679142327 - 33.94792626631624 - 51.61979249013329 + -0.03335 + 51.6996 + 28.21933806852695 + 34.05244126896145 + 51.63689768466914 35 - 1446.969833067415 + 3873.625454957946 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_09B76AF35231BF14491C + + -0.03848996120356829,1,25.78451729971917 + + + + Fitzory Surgery Chelmsford + + 0.474960331146792 + 51.73517761738581 + 40.78990233500093 + 0 + 0 + 35 + 829.7059538363828 + absolute + + #__managed_style_0E0C41AA9431BF9E7CDA - -0.213735727163469,51.6508233199992,115.5282869113015 + 0.473230589786886,51.73593592005771,38.36438983225385 - - Barnet Hospital Emergency Department + + Brentwood Community Hospital - -0.2142299080354926 - 51.65015280865894 - 116.3103679142327 - 33.94792626631624 - 51.61979249013329 + 0.3171528392735157 + 51.62609308593774 + 99.40971056935952 + 0 + 0 35 - 1446.969833067415 + 9806.023979805177 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - -0.2161576826493854,51.65055615262246,125.5996772205984 + 0.3165310777240293,51.62350362985205,109.6301263398982 - - Hadley Wood Hospital + + Mayflower Community Hospital - -0.1981320364942063 - 51.65279534597052 - 125.0634923173999 - 33.95924878558147 - 51.61956884043195 + 0.4023120334724561 + 51.62731403373353 + 60.22327431393138 + 0 + 0 35 - 1415.242666276609 + 5621.724128820934 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - -0.1969832535628527,51.65449483924015,112.7852073322038 + 0.4050319797390082,51.62170280073786,74.70768879269713 - - Medstar Clinic + + West Horndon Surgery - -0.1504930494292478 - 51.61739661253369 - 52.08032173071229 - 33.97802065777326 - 51.61813033259048 + 0.3560545232035661 + 51.56780143023479 + 11.8024814363113 + 0 + 0 35 - 1211.147772304685 + 4198.395910652471 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - -0.1514262105082491,51.61601546985334,60.94665359539616 + 0.3478919772586697,51.56991740445563,11.81273275657717 - - Lordship Lane Primary Care Centre + + Orsett Hospital - -0.08535541171442618 - 51.59570416495118 - 14.86720000060767 - 34.00430616452158 - 51.62460473348132 + 0.3246751037585205 + 51.55178329697734 + 4.008712259332912 + 0 + 0 35 - 2129.647572840331 + 23217.31797739863 absolute - #__managed_style_06A96EF91C31BF144915 + #__managed_style_0E0C41AA9431BF9E7CDA - -0.0805596990899683,51.5972710103994,21.36209261262719 + 0.3662846514279683,51.50992194663591,28.58734636932077 - - Cheshunt Community Hospital + + Basildon University Hospital - -0.03335 - 51.6996 - 28.21933806852695 - 34.05244126896145 - 51.63689768466914 + 0.4683344842514447 + 51.55814670533533 + 62.20367310984593 + 0 + 0 35 - 3873.625454957946 + 5148.914823020459 absolute - #__managed_style_09B76AF35231BF14491C + #__managed_style_0E0C41AA9431BF9E7CDA - -0.03848996120356829,1,25.78451729971917 + 0.4518533224587951,51.55800000431004,57.89818970777221 + + + + Sutherland Lodge Surgery + + 0.4790806956315974 + 51.73013599557864 + 22.04054520405848 + 0 + 0 + 35 + 2563.299715178437 + absolute + + #__managed_style_0E0C41AA9431BF9E7CDA + + 0.482412970012287,51.7257098800565,30.20589758874257 + + + + Braintree Community Hospital + + 0.5484712809762371 + 51.87140860174407 + 45.57400011538562 + 0 + 0 + 35 + 5378.982349414146 + absolute + + #__managed_style_0E0C41AA9431BF9E7CDA + + 0.5404728217711163,51.87983379657575,73.71777320795582 + + + + Halstead Hospital + + 0.6308253311851253 + 51.94110862866791 + 55.87094588961648 + 0 + 0 + 35 + 4196.559132258408 + absolute + + #__managed_style_0E0C41AA9431BF9E7CDA + + 0.6379421359890148,51.94822718909322,56.15721830449306 + + + + Colchester General Hospital + + 0.8999150581272652 + 51.91029998454125 + 43.54285943894751 + 0 + 0 + 35 + 614.4730181369232 + absolute + + #__managed_style_0E0C41AA9431BF9E7CDA + + 0.8993085991404359,51.91038853812569,52.05996642334027 diff --git a/Destinations.tsp b/Destinations.tsp index 47c9f2d018..3605f1f141 100644 --- a/Destinations.tsp +++ b/Destinations.tsp @@ -1,35 +1,35 @@ NAME: example TYPE: TSP -DIMENSION: 30 +DIMENSION: 29 EDGE_WEIGHT_TYPE: EUC_2D NODE_COORD_SECTION -1 51.6497469421364 -0.1951169862852115 -2 51.77432116677244 0.4661826118043533 -3 51.90985612864645 0.8989016354739056 -4 51.90631333268821 0.8950007512019129 -5 51.90668078352024 0.9020700978708827 -6 51.75341033368938 0.4847439958367916 -7 51.75595480607432 0.4860906915350229 -8 51.74716663521045 0.4851154704670301 -9 51.70491929118251 0.1237980769230785 -10 51.76952006829818 0.08539556146978197 -11 51.77176739550571 0.0868200246143358 -12 51.75607366423915 0.1129865782056449 -13 51.80818175439255 0.1356597399818305 -14 51.55385927682786 0.6877328222924616 -15 51.76043771309943 -0.3435461023351755 -16 51.7516592203038 -0.4691092344696746 -17 51.81044035125617 -0.8061987654715064 -18 51.79736510287374 -0.8014090401785613 -19 51.79724865426316 -0.8000927812905456 -20 51.70695925794588 0.5035843063186717 -21 51.73092405457083 0.4710096422132502 -22 51.72999144599143 0.4663354223901122 -23 51.72642076891589 0.456043285327947 -24 51.73261225563316 0.42651098901098 -25 51.6508233199992 -0.213735727163469 -26 51.65055615262246 -0.2161576826493854 -27 51.65449483924015 -0.1969832535628527 -28 51.61601546985334 -0.1514262105082491 -29 51.5972710103994 -0.0805596990899683 +1 51.77432116677244 0.4661826118043533 +2 51.90985612864645 0.8989016354739056 +3 51.90631333268821 0.8950007512019129 +4 51.90668078352024 0.9020700978708827 +5 51.75341033368938 0.4847439958367916 +6 51.75595480607432 0.4860906915350229 +7 51.74716663521045 0.4851154704670301 +8 51.70288283015128 0.1255747078023273 +9 51.76912716012718 0.08565868894554463 +10 51.77177470864583 0.08681342944926174 +11 51.75607366423915 0.1129865782056449 +12 51.80828291123409 0.1357804869768531 +13 51.55385927682786 0.6877328222924616 +14 51.70695925794588 0.5035843063186717 +15 51.73092405457083 0.4710096422132502 +16 51.72999144599143 0.4663354223901122 +17 51.72642076891589 0.456043285327947 +18 51.73261225563316 0.42651098901098 +19 1.0 -0.03848996120356829 +20 51.73593592005771 0.473230589786886 +21 51.62350362985205 0.3165310777240293 +22 51.62170280073786 0.4050319797390082 +23 51.56991740445563 0.3478919772586697 +24 51.50992194663591 0.3662846514279683 +25 51.55800000431004 0.4518533224587951 +26 51.7257098800565 0.482412970012287 +27 51.87983379657575 0.5404728217711163 +28 51.94822718909322 0.6379421359890148 +29 51.91038853812569 0.8993085991404359 EOF From 569c5c800b6d55a2a995deeec37a8c995d88fd44 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 7 Jul 2024 00:19:56 +0100 Subject: [PATCH 20/33] Update Destinations.tsp --- Destinations.tsp | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/Destinations.tsp b/Destinations.tsp index 3605f1f141..016d8c5ef7 100644 --- a/Destinations.tsp +++ b/Destinations.tsp @@ -21,15 +21,14 @@ NODE_COORD_SECTION 16 51.72999144599143 0.4663354223901122 17 51.72642076891589 0.456043285327947 18 51.73261225563316 0.42651098901098 -19 1.0 -0.03848996120356829 -20 51.73593592005771 0.473230589786886 -21 51.62350362985205 0.3165310777240293 -22 51.62170280073786 0.4050319797390082 -23 51.56991740445563 0.3478919772586697 -24 51.50992194663591 0.3662846514279683 -25 51.55800000431004 0.4518533224587951 -26 51.7257098800565 0.482412970012287 -27 51.87983379657575 0.5404728217711163 -28 51.94822718909322 0.6379421359890148 -29 51.91038853812569 0.8993085991404359 +19 51.73593592005771 0.473230589786886 +20 51.62350362985205 0.3165310777240293 +21 51.62170280073786 0.4050319797390082 +22 51.56991740445563 0.3478919772586697 +23 51.50992194663591 0.3662846514279683 +24 51.55800000431004 0.4518533224587951 +25 51.7257098800565 0.482412970012287 +26 51.87983379657575 0.5404728217711163 +27 51.94822718909322 0.6379421359890148 +28 51.91038853812569 0.8993085991404359 EOF From 21f7d8899ec0c5360c24b090f7d2cda6d89fef3d Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Sun, 7 Jul 2024 00:31:41 +0100 Subject: [PATCH 21/33] Update Destinations.tsp From 0cad995923db03c1ff775ba3ced67a64deb33afc Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:10:57 +0100 Subject: [PATCH 22/33] Add files via upload --- PathPlanning/DynamicWindowApproach/Config.py | 47 +++++++++++++++++++ .../DynamicWindowApproach/RobotType.py | 10 ++++ .../DynamicWindowApproach/dwa_control.py | 8 ++++ .../DynamicWindowApproach/plot_robot.py | 36 ++++++++++++++ 4 files changed, 101 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/Config.py create mode 100644 PathPlanning/DynamicWindowApproach/RobotType.py create mode 100644 PathPlanning/DynamicWindowApproach/dwa_control.py create mode 100644 PathPlanning/DynamicWindowApproach/plot_robot.py diff --git a/PathPlanning/DynamicWindowApproach/Config.py b/PathPlanning/DynamicWindowApproach/Config.py new file mode 100644 index 0000000000..2178b95b63 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Config.py @@ -0,0 +1,47 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function +def read_fences(file_path): + """Reads fence positions from a TSP file format and converts them to obstacles.""" + fences = [] + with open(file_path, 'r') as f: + reading_nodes = False + for line in f: + if "NODE_COORD_SECTION" in line: + reading_nodes = True + elif "EOF" in line: + break + elif reading_nodes: + _, x, y = line.split() + fences.append([float(x), float(y)]) + return fences + +class Config: + def __init__(self, fences_file): + self.max_speed = 1.0 # [m/s] + self.min_speed = -0.5 # [m/s] + self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s] + self.max_accel = 0.2 # [m/ss] + self.max_delta_yaw_rate = 40.0 * math.pi / 180.0 # [rad/ss] + self.v_resolution = 0.01 # [m/s] + self.yaw_rate_resolution = 0.1 * math.pi / 180.0 # [rad/s] + self.dt = 0.1 # [s] Time tick for motion prediction + self.predict_time = 3.0 # [s] + self.to_goal_cost_gain = 0.15 + self.speed_cost_gain = 1.0 + self.obstacle_cost_gain = 1.0 + self.robot_stuck_flag_cons = 0.001 # constant to prevent robot stucked + self.robot_type = RobotType.circle + self.robot_radius = 1.0 # [m] for collision check + self.robot_width = 0.5 # [m] for collision check + self.robot_length = 1.2 # [m] for collision check + + # Read the obstacles from the fences file + self.ob = np.array(read_fences(fences_file)) + # Usage example +FENCES_FILE = '/home/dell/ALNS/Fences.tsp' +config = Config(FENCES_FILE) + +print("Obstacle coordinates:") +print(config.ob) diff --git a/PathPlanning/DynamicWindowApproach/RobotType.py b/PathPlanning/DynamicWindowApproach/RobotType.py new file mode 100644 index 0000000000..698aeb9358 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/RobotType.py @@ -0,0 +1,10 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function +import numpy as np +import math + +class RobotType: + circle = 1 + rectangle = 2 diff --git a/PathPlanning/DynamicWindowApproach/dwa_control.py b/PathPlanning/DynamicWindowApproach/dwa_control.py new file mode 100644 index 0000000000..cf45268e20 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/dwa_control.py @@ -0,0 +1,8 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function +def dwa_control(x, config, goal, ob): + dw = calc_dynamic_window(x, config) + u, trajectory = calc_control_and_trajectory(x, dw, config, goal, ob) + return u, trajectory diff --git a/PathPlanning/DynamicWindowApproach/plot_robot.py b/PathPlanning/DynamicWindowApproach/plot_robot.py new file mode 100644 index 0000000000..2eb4cd56be --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/plot_robot.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +import time +import math +import sys +import pathlib +import threading +import matplotlib.pyplot as plt +import numpy as np +import argparse +import random +from enum import Enum +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +def plot_robot(x, y, yaw, config): + if config.robot_type == RobotType.rectangle: + outline = np.array([[-config.robot_length / 2, config.robot_length / 2, + (config.robot_length / 2), -config.robot_length / 2, + -config.robot_length / 2], + [config.robot_width / 2, config.robot_width / 2, + - config.robot_width / 2, -config.robot_width / 2, + config.robot_width / 2]]) + Rot1 = np.array([[math.cos(yaw), math.sin(yaw)], + [-math.sin(yaw), math.cos(yaw)]]) + outline = (outline.T.dot(Rot1)).T + outline[0, :] += x + outline[1, :] += y + plt.plot(np.array(outline[0, :]).flatten(), + np.array(outline[1, :]).flatten(), "-k") + elif config.robot_type == RobotType.circle: + circle = plt.Circle((x, y), config.robot_radius, color="b") + plt.gcf().gca().add_artist(circle) + out_x, out_y = (np.array([x, y]) + + np.array([np.cos(yaw), np.sin(yaw)]) * config.robot_radius) + plt.plot([x, out_x], [y, out_y], "-k") From 82c0ab5b29470449bb5db8b9e8f929bb8f222438 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:14:30 +0100 Subject: [PATCH 23/33] Create Readme file --- PathPlanning/DynamicWindowApproach/Readme file | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/Readme file diff --git a/PathPlanning/DynamicWindowApproach/Readme file b/PathPlanning/DynamicWindowApproach/Readme file new file mode 100644 index 0000000000..f96388fd99 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Readme file @@ -0,0 +1,6 @@ +~/ardupilot$ ./libraries/SITL/examples/Airsim/follow-1-copter.sh +mavproxy.py --master=udpin:127.0.0.1:14550 --console --out=udpout:127.0.0.1:14552 +./mavproxy_kml.py + +~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 take0ff_arm.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 +~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 Unreal_Ardupilo_Drones_DWA.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 From 1f09ff6dd78dbc92968b99ab83ec8adc48e945ec Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:15:36 +0100 Subject: [PATCH 24/33] Add files via upload --- .../Essex_Hospitals_NoFlyZones.kml | 25876 ++++++++++++++++ .../DynamicWindowApproach/mavproxy_kml.py | 30 + 2 files changed, 25906 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/Essex_Hospitals_NoFlyZones.kml create mode 100644 PathPlanning/DynamicWindowApproach/mavproxy_kml.py diff --git a/PathPlanning/DynamicWindowApproach/Essex_Hospitals_NoFlyZones.kml b/PathPlanning/DynamicWindowApproach/Essex_Hospitals_NoFlyZones.kml new file mode 100644 index 0000000000..206154702a --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Essex_Hospitals_NoFlyZones.kml @@ -0,0 +1,25876 @@ + + + + NATS AIM on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.
+ The content of this file is not guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free.]]>
+ + 2024-06-13 + 2024-06-13 + + + + + + + normal + #__managed_style_111482045631BD754BC2 + + + highlight + #__managed_style_284C0E702C31BD754BC2 + + + + + + + + + + + normal + #__managed_style_199B32D61131BD208B69 + + + highlight + #__managed_style_2E7C1EAAA231BD208B69 + + + + + + + + + + normal + #rdpstyle + + + highlight + #highlightStyle + + + + Airspaces + + Danger + + EGD001 TREVOSE HEAD + 501918N 0053042W -
502400N 0053900W -
503200N 0053400W -
503930N 0052400W -
504300N 0051230W -
503830N 0050430W -
501918N 0053042W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552415.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5116666667,50.3216666667,304.8 -5.075,50.6416666667,304.8 -5.2083333333,50.7166666667,304.8 -5.4,50.6583333333,304.8 -5.5666666667,50.5333333333,304.8 -5.65,50.39999999999999,304.8 -5.5116666667,50.3216666667,304.8 + + + + +
+ + EGD003 PLYMOUTH + 501001N 0034740W -
500339N 0033430W -
494105N 0034912W -
493719N 0040938W -
501001N 0034740W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.7944444444,50.16694444440001,6705.599999999999 -4.1605555556,49.6219444444,6705.599999999999 -3.82,49.68472222220001,6705.599999999999 -3.575,50.0608333333,6705.599999999999 -3.7944444444,50.16694444440001,6705.599999999999 + + + + +
+ + EGD004 PLYMOUTH + 500339N 0033430W -
500103N 0032910W -
494653N 0031655W -
494105N 0034912W -
500339N 0033430W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.575,50.0608333333,6705.599999999999 -3.82,49.68472222220001,6705.599999999999 -3.281944444400001,49.7813888889,6705.599999999999 -3.4861111111,50.0175,6705.599999999999 -3.575,50.0608333333,6705.599999999999 + + + + +
+ + EGD005A PREDANNACK + A circle, 3 NM radius, centred at 500007N 0051354W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2317694444,50.0519840728,2438.4 -5.2382609639,50.0518087079,2438.4 -5.244706809,50.0512838469,2438.4 -5.2510616297,50.0504131826,2438.4 -5.2572807223,50.0492028405,2438.4 -5.2633203464,50.04766133530001,2438.4 -5.2691380355,50.04579951060001,2438.4 -5.2746928974,50.0436304617,2438.4 -5.2799459031,50.0411694431,2438.4 -5.2848601634,50.0384337598,2438.4 -5.2894011878,50.03544264570001,2438.4 -5.2935371276,50.0322171262,2438.4 -5.2972389989,50.0287798704,2438.4 -5.3004808854,50.0251550305,2438.4 -5.3032401186,50.0213680712,2438.4 -5.3054974349,50.01744559,2438.4 -5.3072371079,50.0134151297,2438.4 -5.308447056,50.00930498430001,2438.4 -5.3091189239,50.0051440001,2438.4 -5.3092481369,50.0009613725,2438.4 -5.3088339296,49.9967864416,2438.4 -5.3078793473,49.9926484858,2438.4 -5.3063912206,49.98857651649999,2438.4 -5.3043801136,49.98459907579999,2438.4 -5.3018602465,49.9807440358,2438.4 -5.2988493928,49.97703840469999,2438.4 -5.2953687514,49.9735081377,2438.4 -5.2914427962,49.9701779565,2438.4 -5.2870991023,49.9670711763,2438.4 -5.2823681521,49.9642095444,2438.4 -5.2772831207,49.9616130881,2438.4 -5.2718796434,49.9592999758,2438.4 -5.2661955671,49.957286391,2438.4 -5.2602706859,49.95558641960001,2438.4 -5.2541464643,49.9542119522,2438.4 -5.2478657491,49.9531726018,2438.4 -5.2414724716,49.9524756371,2438.4 -5.2350113432,49.95212593200001,2438.4 -5.2285275456,49.95212593200001,2438.4 -5.2220664173,49.9524756371,2438.4 -5.2156731398,49.9531726018,2438.4 -5.2093924246,49.9542119522,2438.4 -5.203268203,49.95558641960001,2438.4 -5.1973433218,49.957286391,2438.4 -5.1916592454,49.9592999758,2438.4 -5.1862557682,49.9616130881,2438.4 -5.1811707367,49.9642095444,2438.4 -5.1764397866,49.9670711763,2438.4 -5.1720960927,49.9701779565,2438.4 -5.1681701375,49.9735081377,2438.4 -5.1646894961,49.97703840469999,2438.4 -5.1616786423,49.9807440358,2438.4 -5.1591587753,49.98459907579999,2438.4 -5.1571476683,49.98857651649999,2438.4 -5.1556595416,49.9926484858,2438.4 -5.1547049593,49.9967864416,2438.4 -5.154290752,50.0009613725,2438.4 -5.154419965,50.0051440001,2438.4 -5.1550918329,50.00930498430001,2438.4 -5.156301781,50.0134151297,2438.4 -5.158041454,50.01744559,2438.4 -5.1602987703,50.0213680712,2438.4 -5.1630580035,50.0251550305,2438.4 -5.16629989,50.0287798704,2438.4 -5.1700017613,50.0322171262,2438.4 -5.1741377011,50.03544264570001,2438.4 -5.1786787255,50.0384337598,2438.4 -5.1835929857,50.0411694431,2438.4 -5.1888459915,50.0436304617,2438.4 -5.1944008533,50.04579951060001,2438.4 -5.2002185425,50.04766133530001,2438.4 -5.2062581666,50.0492028405,2438.4 -5.2124772592,50.0504131826,2438.4 -5.2188320799,50.0512838469,2438.4 -5.225277925,50.0518087079,2438.4 -5.2317694444,50.0519840728,2438.4 + + + + +
+ + EGD005B PREDANNACK CORRIDOR + 500208N 0051722W -
495818N 0052242W -
495124N 0051200W -
495629N 0050728W -
495809N 0051024W thence clockwise by the arc of a circle radius 3 NM centred on 500007N 0051354W to -
500208N 0051722W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Culdrose APP on 134.050 MHz when open; at other times SUAAIS: Swanwick Mil via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2893774722,50.0354596389,2438.4 -5.3783333333,49.97166666670001,2438.4 -5.2,49.8566666667,2438.4 -5.1243299444,49.94131175,2438.4 -5.1732655,49.969289,2438.4 -5.1776868569,49.9662693871,2438.4 -5.1824813042,49.9634969443,2438.4 -5.1876157091,49.96099079620001,2438.4 -5.1930546103,49.9587682276,2438.4 -5.198760463,49.9568445653,2438.4 -5.2046938963,49.9552330729,2438.4 -5.2108139835,49.95394486080001,2438.4 -5.2170785222,49.9529888094,2438.4 -5.2234443235,49.9523715092,2438.4 -5.2298675064,49.95209721499999,2438.4 -5.2363037984,49.95216781749999,2438.4 -5.2427088373,49.9525828301,2438.4 -5.2490384744,49.9533393922,2438.4 -5.2552490759,49.9544322888,2438.4 -5.2612978212,49.9558539861,2438.4 -5.2671429954,49.9575946829,2438.4 -5.2727442751,49.95964237780001,2438.4 -5.2780630047,49.9619829511,2438.4 -5.2830624614,49.9646002613,2438.4 -5.2877081082,49.9674762558,2438.4 -5.2919678313,49.9705910944,2438.4 -5.2958121626,49.9739232851,2438.4 -5.2992144834,49.9774498319,2438.4 -5.3021512098,49.9811463922,2438.4 -5.3046019571,49.9849874443,2438.4 -5.3065496835,49.9889464626,2438.4 -5.3079808099,49.9929961005,2438.4 -5.3088853174,49.9971083784,2438.4 -5.30925682,50.0012548768,2438.4 -5.309092612,50.0054069326,2438.4 -5.3083936908,50.0095358368,2438.4 -5.3071647539,50.013613033,2438.4 -5.3054141696,50.0176103157,2438.4 -5.3031539236,50.0215000252,2438.4 -5.3003995384,50.0252552394,2438.4 -5.2971699697,50.0288499612,2438.4 -5.2934874772,50.0322592989,2438.4 -5.2893774722,50.0354596389,2438.4 + + + + +
+ + EGD006A FALMOUTH BAY + 501244N 0044659W -
500726N 0044228W -
500000N 0045430W -
500924N 0045430W -
501244N 0044659W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7830555556,50.21222222219999,6705.599999999999 -4.9083333333,50.1566666667,6705.599999999999 -4.9083333333,50,6705.599999999999 -4.7077777778,50.1238888889,6705.599999999999 -4.7830555556,50.21222222219999,6705.599999999999 + + + + +
+ + EGD006B FALMOUTH BAY + 495907N 0050506W -
500500N 0045948W -
500924N 0045430W -
500000N 0045430W -
495646N 0045634W -
495907N 0050506W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0849987222,49.9851711667,2438.4 -4.9428074167,49.9462036944,2438.4 -4.9083333333,50,2438.4 -4.9083333333,50.1566666667,2438.4 -4.9966666667,50.0833333333,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + +
+ + EGD006C FALMOUTH BAY + 495907N 0050506W -
495124N 0051200W -
495124N 0050000W -
495646N 0045634W -
495907N 0050506W
Upper limit: 8000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Culdrose Operations, Tel: 01326-552201.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0849987222,49.9851711667,2438.4 -5.2,49.8566666667,2438.4 -5,49.8566666667,2438.4 -4.9428074167,49.9462036944,2438.4 -5.0849987222,49.9851711667,2438.4 + + + + +
+ + EGD007A FOWEY + 501801N 0043643W -
501820N 0043152W -
501857N 0042738W -
501550N 0042458W -
500922N 0044407W -
501202N 0044623W -
501801N 0043643W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6119444444,50.3002777778,6705.599999999999 -4.7730555556,50.2005555556,6705.599999999999 -4.7352777778,50.1561111111,6705.599999999999 -4.4161111111,50.26388888890001,6705.599999999999 -4.4605555556,50.31583333330001,6705.599999999999 -4.5311111111,50.30555555560001,6705.599999999999 -4.6119444444,50.3002777778,6705.599999999999 + + + + +
+ + EGD007B FOWEY + 501550N 0042458W -
501342N 0042309W -
500726N 0044228W -
500922N 0044407W -
501550N 0042458W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4161111111,50.26388888890001,6705.599999999999 -4.7352777778,50.1561111111,6705.599999999999 -4.7077777778,50.1238888889,6705.599999999999 -4.3858333333,50.2283333333,6705.599999999999 -4.4161111111,50.26388888890001,6705.599999999999 + + + + +
+ + EGD007C FOWEY INNER + 501733N 0044334W -
501801N 0043643W -
501202N 0044623W -
501244N 0044659W -
501414N 0044441W -
501647N 0044447W -
501733N 0044334W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards..

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7261111111,50.2925,609.6 -4.7463888889,50.27972222219999,609.6 -4.7447222222,50.23722222220001,609.6 -4.7830555556,50.21222222219999,609.6 -4.7730555556,50.2005555556,609.6 -4.6119444444,50.3002777778,609.6 -4.7261111111,50.2925,609.6 + + + + +
+ + EGD008A PLYMOUTH + 495654N 0045629W -
493715N 0041003W -
492745N 0050000W -
495124N 0050000W -
495654N 0045629W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9413888889,49.94833333330001,6705.599999999999 -5,49.8566666667,6705.599999999999 -5,49.4625,6705.599999999999 -4.1675,49.6208333333,6705.599999999999 -4.9413888889,49.94833333330001,6705.599999999999 + + + + +
+ + EGD008B PLYMOUTH + 494740N 0043430W -
494438N 0040446W -
493719N 0040938W -
493715N 0041003W -
494740N 0043430W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.575,49.79444444440001,6705.599999999999 -4.1675,49.6208333333,6705.599999999999 -4.1605555556,49.6219444444,6705.599999999999 -4.0794444444,49.7438888889,6705.599999999999 -4.575,49.79444444440001,6705.599999999999 + + + + +
+ + EGD008C PLYMOUTH + 501140N 0042931W thence anti-clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to
500623N 0035008W -
494438N 0040446W -
494740N 0043430W -
495654N 0045629W -
500000N 0045430W -
500726N 0044228W -
501140N 0042931W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4919444444,50.1944444444,16764 -4.7077777778,50.1238888889,16764 -4.9083333333,50,16764 -4.9413888889,49.94833333330001,16764 -4.575,49.79444444440001,16764 -4.0794444444,49.7438888889,16764 -3.8355555556,50.1063888889,16764 -3.8477298237,50.10032261750001,16764 -3.8600996985,50.094429589,16764 -3.8727887629,50.08882582250001,16764 -3.8857806495,50.0835184994,16764 -3.8990586201,50.0785144188,16764 -3.9126055863,50.0738199893,16764 -3.926404131,50.0694412212,16764 -3.9404365295,50.06538371910001,16764 -3.9546847725,50.061652675,16764 -3.9691305873,50.058252862,16764 -3.9837554609,50.0551886287,16764 -3.9985406625,50.05246389340001,16764 -4.0134672665,50.05008214,16764 -4.0285161756,50.0480464131,16764 -4.0436681441,50.0463593148,16764 -4.0589038012,50.0450230012,16764 -4.0742036748,50.04403918,16764 -4.0895482148,50.0434091085,16764 -4.104917817,50.0431335916,16764 -4.120292847,50.0432129814,16764 -4.1356536637,50.0436471765,16764 -4.1509806431,50.0444356221,16764 -4.1662542024,50.04557731069999,16764 -4.1814548235,50.0470707833,16764 -4.1965630767,50.04891413150001,16764 -4.2115596442,50.0511049992,16764 -4.2264253437,50.05364058589999,16764 -4.241141152,50.05651765,16764 -4.2556882278,50.05973251270001,16764 -4.2700479348,50.0632810627,16764 -4.2842018648,50.0671587608,16764 -4.2981318601,50.0713606457,16764 -4.311820036,50.07588133990001,16764 -4.3252488027,50.0807150566,16764 -4.3384008876,50.0858556064,16764 -4.3512593561,50.09129640490001,16764 -4.3638076335,50.097030481,16764 -4.3760295253,50.1030504853,16764 -4.387909238,50.109348699,16764 -4.3994313989,50.11591704389999,16764 -4.4105810759,50.1227470915,16764 -4.4213437965,50.12983007439999,16764 -4.4317055664,50.1371568961,16764 -4.4416528883,50.1447181433,16764 -4.4511727785,50.1525040966,16764 -4.4602527853,50.1605047435,16764 -4.4688810044,50.1687097899,16764 -4.4770460956,50.1771086739,16764 -4.484737298,50.1856905783,16764 -4.4919444444,50.1944444444,16764 + + + + +
+ + EGD009A WEMBURY + 501904N 0040633W -
501001N 0034740W -
500623N 0035008W thence clockwise by the arc of a circle radius 16.5 NM centred on 501904N 0040633W to
501140N 0042931W -
501904N 0040633W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC – Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1091666667,50.3177777778,16764 -4.4919444444,50.1944444444,16764 -4.4849292755,50.1856225616,16764 -4.477234108,50.1770362709,16764 -4.4690648117,50.1686330948,16764 -4.460432153,50.160423856,16764 -4.4513474783,50.152419122,16764 -4.4418226976,50.1446291917,16764 -4.4318702695,50.1370640831,16764 -4.421503184,50.1297335201,16764 -4.4107349457,50.1226469211,16764 -4.3995795559,50.1158133869,16764 -4.3880514944,50.1092416896,16764 -4.376165701,50.1029402616,16764 -4.3639375563,50.0969171856,16764 -4.3513828619,50.0911801839,16764 -4.3385178203,50.08573660980001,16764 -4.3253590148,50.0805934379,16764 -4.3119233883,50.0757572558,16764 -4.2982282225,50.071234256,16764 -4.2842911159,50.06703022840001,16764 -4.2701299621,50.0631505531,16764 -4.2557629282,50.0596001938,16764 -4.2412084315,50.056383692,16764 -4.2264851176,50.0535051612,16764 -4.2116118373,50.0509682819,16764 -4.1966076236,50.0487762975,16764 -4.1814916682,50.0469320097,16764 -4.1662832985,50.04543777580001,16764 -4.1510019541,50.0442955053,16764 -4.1356671629,50.0435066578,16764 -4.1202985175,50.0430722415,16764 -4.1049156516,50.0429928112,16764 -4.0895382162,50.0432684685,16764 -4.0741858556,50.0438988612,16764 -4.0588781838,50.0448831838,16764 -4.0436347606,50.04622017849999,16764 -4.0284750679,50.0479081368,16764 -4.0134184863,50.04994490129999,16764 -3.9984842711,50.0523278689,16764 -3.9836915291,50.05505399319999,16764 -3.9690591956,50.0581197887,16764 -3.9546060106,50.06152133509999,16764 -3.940350496599999,50.0652542816,16764 -3.9263109353,50.0693138528,16764 -3.9125053453,50.0736948539,16764 -3.898951460000001,50.07839167760001,16764 -3.8856667055,50.0833983106,16764 -3.8726681787,50.0887083411,16764 -3.8599726265,50.0943149665,16764 -3.8475964243,50.1002110019,16764 -3.8355555556,50.1063888889,16764 -3.7944444444,50.16694444440001,16764 -4.1091666667,50.3177777778,16764 + + + + +
+ + EGD009B WEMBURY + 501342N 0042309W -
501951N 0041015W thence clockwise by the arc of a circle radius 2.5 NM centred on 501904N 0040633W to
501735N 0040325W -
501904N 0040633W -
501342N 0042309W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC – Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 121.250 MHz when open; at other times Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Plymouth Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3858333333,50.2283333333,6705.599999999999 -4.1091666667,50.3177777778,6705.599999999999 -4.0569444444,50.29305555560001,6705.599999999999 -4.0536641121,50.2962012969,6705.599999999999 -4.0508306672,50.2995200299,6705.599999999999 -4.0484794125,50.3029899108,6705.599999999999 -4.0466298918,50.30658225509999,6705.599999999999 -4.0452975128,50.3102673594,6705.599999999999 -4.0444934154,50.31401474640001,6705.599999999999 -4.0442243764,50.3177934166,6705.599999999999 -4.0444927492,50.3215721043,6705.599999999999 -4.0452964397,50.32531953660001,6705.599999999999 -4.0466289201,50.32900469150001,6705.599999999999 -4.0484792784,50.3325970559,6705.599999999999 -4.050832305,50.33606687810001,6705.599999999999 -4.0536686156,50.339385415,6705.599999999999 -4.0569648077,50.3425251708,6705.599999999999 -4.0606936531,50.3454601258,6705.599999999999 -4.0648243209,50.34816595309999,6705.599999999999 -4.0693226319,50.3506202208,6705.599999999999 -4.0741513417,50.3528025791,6705.599999999999 -4.0792704488,50.3546949305,6705.599999999999 -4.0846375278,50.35628158019999,6705.599999999999 -4.0902080822,50.3575493674,6705.599999999999 -4.0959359153,50.3584877753,6705.599999999999 -4.1017735161,50.3590890188,6705.599999999999 -4.1076724557,50.3593481099,6705.599999999999 -4.1135837926,50.3592628989,6705.599999999999 -4.1194584815,50.3588340927,6705.599999999999 -4.1252477834,50.3580652491,6705.599999999999 -4.1309036735,50.3569627465,6705.599999999999 -4.136379242,50.3555357309,6705.599999999999 -4.1416290858,50.35379603959999,6705.599999999999 -4.1466096878,50.351758102,6705.599999999999 -4.1512797789,50.3494388193,6705.599999999999 -4.1556006814,50.3468574234,6705.599999999999 -4.1595366302,50.3440353162,6705.599999999999 -4.163055069,50.3409958917,6705.599999999999 -4.1661269193,50.3377643405,6705.599999999999 -4.1687268196,50.3343674403,6705.599999999999 -4.1708333333,50.3308333333,6705.599999999999 -4.3858333333,50.2283333333,6705.599999999999 + + + + +
+ + EGD011A OKEHAMPTON + 504226N 0040146W -
504311N 0035854W -
503937N 0035613W -
503725N 0035712W -
503744N 0035801W -
503729N 0040101W -
504019N 0040341W -
504226N 0040146W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 10000 FT ALT.

Vertical Limits: Normally 10000 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1980/949. UAS BVLOS will not be conducted above 10000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0294444444,50.7072222222,7345.68 -4.0613888889,50.6719444444,7345.68 -4.0169444444,50.6247222222,7345.68 -3.9669444444,50.62888888890001,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9369444444,50.6602777778,7345.68 -3.9816666667,50.7197222222,7345.68 -4.0294444444,50.7072222222,7345.68 + + + + +
+ + EGD011B WILLSWORTHY + 504019N 0040341W -
503729N 0040101W -
503726N 0040136W -
503550N 0040444W -
503747N 0040558W -
504019N 0040341W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 4500 FT ALT.

Vertical Limits: Normally 4500 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1980/950. UAS BVLOS will not be conducted above 4500 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0613888889,50.6719444444,7345.68 -4.0994444444,50.6297222222,7345.68 -4.0788888889,50.5972222222,7345.68 -4.0266666667,50.62388888890001,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0613888889,50.6719444444,7345.68 + + + + +
+ + EGD011C MERRIVALE + 503726N 0040136W -
503729N 0040101W -
503744N 0035801W -
503725N 0035712W -
503426N 0035832W -
503402N 0040336W -
503550N 0040444W -
503726N 0040136W
Upper limit: 24100 FT MSL
Lower limit: SFC
Class: AMC – Manageable above 10000 FT ALT.

Vertical Limits: Normally 10000 FT ALT.

Vertical Limits: OCNL notified to 24100 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01837-657210.

Remarks: SI 1979/1721. UAS BVLOS will not be conducted above 10000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0266666667,50.62388888890001,7345.68 -4.0788888889,50.5972222222,7345.68 -4.06,50.5672222222,7345.68 -3.9755555556,50.57388888890001,7345.68 -3.9533333333,50.6236111111,7345.68 -3.9669444444,50.62888888890001,7345.68 -4.0169444444,50.6247222222,7345.68 -4.0266666667,50.62388888890001,7345.68 + + + + +
+ + EGD012 LYME BAY NORTH + 504220N 0024500W -
503400N 0024500W following the line of latitude to -
503400N 0030500W -
503000N 0031730W -
503650N 0031500W -
504106N 0030544W - then along the coastline to -
504220N 0024500W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.7055555556,5486.400000000001 -2.7539289167,50.70698188890001,5486.400000000001 -2.7687341389,50.71156202780001,5486.400000000001 -2.7852465278,50.7163986111,5486.400000000001 -2.7919162222,50.717073,5486.400000000001 -2.7971543056,50.7168574444,5486.400000000001 -2.8015669444,50.7180863333,5486.400000000001 -2.8077796667,50.71687425,5486.400000000001 -2.8110547222,50.7178408333,5486.400000000001 -2.8169062778,50.7203182778,5486.400000000001 -2.8306950556,50.72291902780001,5486.400000000001 -2.8383291111,50.7219649722,5486.400000000001 -2.8451533056,50.7232648056,5486.400000000001 -2.8632228333,50.7273595556,5486.400000000001 -2.8797339722,50.7303860278,5486.400000000001 -2.896757083299999,50.73223300000001,5486.400000000001 -2.9061245,50.73297002779999,5486.400000000001 -2.9145946944,50.73128499999999,5486.400000000001 -2.9238843611,50.7280638889,5486.400000000001 -2.9262131111,50.72399813890001,5486.400000000001 -2.9284638056,50.72317077780001,5486.400000000001 -2.9318530833,50.7226041111,5486.400000000001 -2.934091083299999,50.72114716669999,5486.400000000001 -2.9342041389,50.7197072222,5486.400000000001 -2.9360313333,50.7189730556,5486.400000000001 -2.9438005278,50.71783113890001,5486.400000000001 -2.9500746944,50.7128335,5486.400000000001 -2.9523317222,50.7123653889,5486.400000000001 -2.9613887778,50.71193130559999,5486.400000000001 -2.962810611100001,50.7121893889,5486.400000000001 -2.96587475,50.7096457222,5486.400000000001 -2.9731907222,50.70724644439999,5486.400000000001 -2.9783781111,50.7046847222,5486.400000000001 -2.9843237222,50.7045447222,5486.400000000001 -2.9877430833,50.7055051389,5486.400000000001 -2.9900088333,50.7054859167,5486.400000000001 -2.9936640833,50.7041956667,5486.400000000001 -2.9989896667,50.7015418889,5486.400000000001 -3.0043338611,50.6997871111,5486.400000000001 -3.0073015,50.6994916667,5486.400000000001 -3.0135101667,50.6984485278,5486.400000000001 -3.0194490278,50.6980369722,5486.400000000001 -3.0249826389,50.6985280833,5486.400000000001 -3.027548888900001,50.6993149722,5486.400000000001 -3.0350669722,50.6998780278,5486.400000000001 -3.0450162778,50.7014981389,5486.400000000001 -3.0491265556,50.7016410833,5486.400000000001 -3.0536555833,50.7015103056,5486.400000000001 -3.0611743056,50.7020716944,5486.400000000001 -3.0658449167,50.7019391389,5486.400000000001 -3.07263125,50.70142719439999,5486.400000000001 -3.074894694400001,50.7013163889,5486.400000000001 -3.077708,50.7004809444,5486.400000000001 -3.0799693056,50.7002801389,5486.400000000001 -3.0816249444,50.6983760556,5486.400000000001 -3.0843944167,50.6956520833,5486.400000000001 -3.0882003056,50.6948971111,5486.400000000001 -3.0891350833,50.6924599722,5486.400000000001 -3.0890976111,50.6908413889,5486.400000000001 -3.0911355,50.68713474999999,5486.400000000001 -3.0919200833,50.68433925,5486.400000000001 -3.0950402778,50.68457980559999,5486.400000000001 -3.095555555599999,50.685,5486.400000000001 -3.25,50.6138888889,5486.400000000001 -3.2916666667,50.5,5486.400000000001 -3.0833333333,50.56666666669999,5486.400000000001 -2.972222222200001,50.56666666669999,5486.400000000001 -2.8611111111,50.56666666669999,5486.400000000001 -2.75,50.56666666669999,5486.400000000001 -2.75,50.7055555556,5486.400000000001 + + + + +
+ + EGD013 LYME BAY + 503400N 0024500W -
500200N 0024500W -
500200N 0025800W -
500800N 0030430W -
502500N 0031730W -
503000N 0031730W -
503400N 0030500W -
503400N 0024500W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.56666666669999,16764 -3.0833333333,50.56666666669999,16764 -3.2916666667,50.5,16764 -3.2916666667,50.4166666667,16764 -3.075000000000001,50.13333333329999,16764 -2.9666666667,50.0333333333,16764 -2.75,50.0333333333,16764 -2.75,50.56666666669999,16764 + + + + +
+ + EGD014 PORTLAND + 503818N 0023424W -
503736N 0023230W -
503530N 0022948W -
503400N 0023124W -
503400N 0023000W -
502931N 0023000W -
503400N 0024500W -
503400N 0024200W -
503700N 0024130W -
503818N 0023424W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 5000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 15000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5733333333,50.6383333333,4572 -2.6916666667,50.6166666667,4572 -2.7,50.56666666669999,4572 -2.75,50.56666666669999,4572 -2.5,50.4919444444,4572 -2.5,50.56666666669999,4572 -2.5233333333,50.56666666669999,4572 -2.4966666667,50.5916666667,4572 -2.5416666667,50.6266666667,4572 -2.5733333333,50.6383333333,4572 + + + + +
+ + EGD015 BOVINGTON + A circle, 500 M radius, centred at 504324N 0021424W
Upper limit: 3600 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01929-403765.

Remarks: SI 1936/118.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.24,50.7278279975,1097.28 -2.2419105304,50.7276613075,1097.28 -2.2436793273,50.7271736038,1097.28 -2.2451751801,50.726401066,1097.28 -2.24628714,50.7254010021,1097.28 -2.2469327516,50.724247594,1097.28 -2.2470641634,50.72302639250001,1097.28 -2.2466716685,50.7218279703,1097.28 -2.2457844129,50.7207412039,1097.28 -2.2444682231,50.7198466836,1097.28 -2.2428207176,50.7192107394,1097.28 -2.240964066,50.7188805253,1097.28 -2.239035934,50.7188805253,1097.28 -2.2371792824,50.7192107394,1097.28 -2.2355317769,50.7198466836,1097.28 -2.2342155871,50.7207412039,1097.28 -2.2333283315,50.7218279703,1097.28 -2.2329358366,50.72302639250001,1097.28 -2.2330672484,50.724247594,1097.28 -2.23371286,50.7254010021,1097.28 -2.2348248199,50.726401066,1097.28 -2.2363206727,50.7271736038,1097.28 -2.2380894696,50.7276613075,1097.28 -2.24,50.7278279975,1097.28 + + + + +
+ + EGD017 PORTLAND + 503400N 0024500W -
502931N 0023000W -
500200N 0023000W -
500200N 0024500W -
503400N 0024500W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.75,50.56666666669999,16764 -2.75,50.0333333333,16764 -2.5,50.0333333333,16764 -2.5,50.4919444444,16764 -2.75,50.56666666669999,16764 + + + + +
+ + EGD021 PORTLAND + 503500N 0022000W -
503500N 0021614W -
503154N 0021624W -
503000N 0021700W -
502918N 0021718W -
502500N 0021500W -
502931N 0023000W -
503000N 0023000W -
503000N 0022000W -
503500N 0022000W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3333333333,50.5833333333,4572 -2.3333333333,50.5,4572 -2.5,50.5,4572 -2.5,50.4919444444,4572 -2.25,50.4166666667,4572 -2.2883333333,50.48833333329999,4572 -2.2833333333,50.5,4572 -2.2733333333,50.5316666667,4572 -2.2705555556,50.5833333333,4572 -2.3333333333,50.5833333333,4572 + + + + +
+ + EGD023 PORTLAND + 502931N 0023000W -
502500N 0021500W -
500200N 0021500W -
500200N 0023000W -
502931N 0023000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit 22000 FT ALT.

Vertical Limit OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5,50.4919444444,16764 -2.5,50.0333333333,16764 -2.25,50.0333333333,16764 -2.25,50.4166666667,16764 -2.5,50.4919444444,16764 + + + + +
+ + EGD026 LULWORTH + 504020N 0020755W -
503950N 0020732W -
503751N 0020753W -
503644N 0020813W -
503503N 0020440W -
503030N 0020043W -
502654N 0020230W -
502500N 0020842W -
502500N 0021500W -
502918N 0021718W -
503000N 0021700W -
503154N 0021624W -
503536N 0021612W -
503700N 0021447W -
503800N 0021430W -
503825N 0021137W -
504028N 0021137W -
504020N 0020755W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: Vertical Limits: OCNL notified to ALT 20000.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS less than 150 KTS).

Service: SUACS not available during notified operating hours.

SUAAIS: Plymouth Military on 124.150 MHz when open, London Information on 124.750 MHz thereafter.

Contact: Booking: FOST Eastern Area Manager, Tel: 01752-557752 for the week before, FOST Duty Operations for the current week. Range Information on 01929-404859 or 01929-404712.

Remarks: SI 1978/1663. Unmanned Aircraft Systems (VLOS/BVLOS
less than 150 KTS) will not be conducted above FL 115 and north of a line
503813N 0021301W, 503746N 0021005W and 503810N 0020750W.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1319444444,50.6722222222,4572 -2.1936111111,50.6744444444,4572 -2.1936111111,50.6402777778,4572 -2.2416666667,50.6333333333,4572 -2.2463888889,50.6166666667,4572 -2.27,50.5933333333,4572 -2.2733333333,50.5316666667,4572 -2.2833333333,50.5,4572 -2.2883333333,50.48833333329999,4572 -2.25,50.4166666667,4572 -2.145,50.4166666667,4572 -2.0416666667,50.4483333333,4572 -2.0119444444,50.50833333330001,4572 -2.0777777778,50.5841666667,4572 -2.1369444444,50.6122222222,4572 -2.1313888889,50.6308333333,4572 -2.1255555556,50.6638888889,4572 -2.1319444444,50.6722222222,4572 + + + + +
+ + EGD031 PORTLAND + 503626N 0015635W -
503000N 0015635W -
503000N 0020058W -
503030N 0020043W -
503412N 0020356W -
503435N 0020320W - then along the coastline in an easterly direction to -
503626N 0015635W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9430555556,50.6072222222,4572 -1.9470027778,50.60444999999999,4572 -1.9484166667,50.6030111111,4572 -1.9506833333,50.5973472222,4572 -1.9489916667,50.5944666667,4572 -1.9540805556,50.59213055560001,4572 -1.9552111111,50.5911416667,4572 -1.9583222222,50.5903333333,4572 -1.9653861111,50.59078611110001,4572 -1.9679277778,50.5904277778,4572 -1.9701888889,50.59078611110001,4572 -1.9738611111,50.5901583333,4572 -1.9772527778,50.5899805556,4572 -1.9812083333,50.5894416667,4572 -1.9857305556,50.5900694444,4572 -1.9877083333,50.5896222222,4572 -1.9964666667,50.59034166670001,4572 -2.0029666667,50.5899805556,4572 -2.0086194444,50.5895305556,4572 -2.014975,50.5888111111,4572 -2.0185083333,50.5880916667,4572 -2.0244416667,50.5871916667,4572 -2.0279722222,50.5851222222,4572 -2.0306527778,50.5829611111,4572 -2.0361611111,50.57981388889999,4572 -2.0394083333,50.5784638889,4572 -2.0427972222,50.5772027778,4572 -2.0454805556,50.5765722222,4572 -2.049575,50.5761194444,4572 -2.0524,50.5754,4572 -2.0555555556,50.5763888889,4572 -2.0655555556,50.57,4572 -2.0119444444,50.50833333330001,4572 -2.0161111111,50.5,4572 -1.9430555556,50.5,4572 -1.9430555556,50.6072222222,4572 + + + + +
+ + EGD036 PORTSMOUTH + 502927N 0011208W -
500000N 0011126W -
500000N 0014301W -
500620N 0014207W -
502927N 0011208W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate or through Southampton or Jersey ATSUs, as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2022222222,50.4908333333,16764 -1.7019444444,50.10555555559999,16764 -1.7169444444,50,16764 -1.1905555556,50,16764 -1.2022222222,50.4908333333,16764 + + + + +
+ + EGD037 PORTSMOUTH + 503700N 0010211W -
503700N 0003938W -
503000N 0003213W -
503000N 0011124W -
503700N 0010211W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0363888889,50.6166666667,16764 -1.19,50.5,16764 -0.5369444444,50.5,16764 -0.6605555556,50.6166666667,16764 -1.0363888889,50.6166666667,16764 + + + + +
+ + EGD038 PORTSMOUTH + 503000N 0011124W -
503000N 0005000W -
500000N 0005000W -
500000N 0011126W -
502927N 0011208W -
503000N 0011124W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.19,50.5,16764 -1.2022222222,50.4908333333,16764 -1.1905555556,50,16764 -0.8333333333000001,50,16764 -0.8333333333000001,50.5,16764 -1.19,50.5,16764 + + + + +
+ + EGD039 PORTSMOUTH + 503000N 0005000W -
503000N 0003213W -
502948N 0003200W -
500000N 0003200W -
500000N 0005000W -
503000N 0005000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8333333333000001,50.5,16764 -0.8333333333000001,50,16764 -0.5333333333,50,16764 -0.5333333333,50.4966666667,16764 -0.5369444444,50.5,16764 -0.8333333333000001,50.5,16764 + + + + +
+ + EGD040 PORTSMOUTH + 502948N 0003200W -
501347N 0001511W -
500000N 0003155W -
500000N 0003200W -
502948N 0003200W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limit: 10000 FT ALT.

Vertical Limit: OCNL notified to altitudes up to 55000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Plymouth Military on 124.150 MHz when open; at other times, Swanwick Mil via London Information on 124.750 MHz. SUAAIS: London Information on 124.750 MHz or 124.600 MHz as appropriate.

Contact: Pre-flight information / Booking: FOST Duty Operations, Tel: 01752-557550.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5333333333,50.4966666667,16764 -0.5333333333,50,16764 -0.5319444444,50,16764 -0.2530555556,50.2297222222,16764 -0.5333333333,50.4966666667,16764 + + + + +
+ + EGD044 LYDD RANGES + 505525N 0005534E -
505328N 0005613E -
505238N 0005359E -
505237N 0005015E -
505420N 0004748E -
505554N 0005009E -
505650N 0005348E -
505525N 0005534E
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225503.

Remarks: SI 1988/1465.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9261111111,50.9236111111,1219.2 0.8966666666999998,50.94722222219999,1219.2 0.8358333333,50.9316666667,1219.2 0.7966666667,50.9055555556,1219.2 0.8375000000000001,50.8769444444,1219.2 0.8997222221999999,50.8772222222,1219.2 0.9369444444,50.8911111111,1219.2 0.9261111111,50.9236111111,1219.2 + + + + +
+ + EGD061 WOODBURY COMMON + A circle, 926 M radius, centred at 504049N 0032051W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Exeter APP on 128.980 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01395-272972.

Remarks: SI 2009/3284.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3475,50.6886019548,457.2 -3.3501377665,50.68843152869999,457.2 -3.3526674871,50.6879272312,457.2 -3.3549855484,50.68710971849999,457.2 -3.3569970187,50.6860124748,457.2 -3.3586195398,50.684680439,457.2 -3.3597866995,50.68316816200001,457.2 -3.3604507489,50.6815375708,457.2 -3.3605845512,50.6798554304,457.2 -3.3601826846,50.6781906099,457.2 -3.3592616556,50.6766112617,457.2 -3.3578592141,50.675182033,457.2 -3.356032801,50.6739614205,457.2 -3.3538571928,50.6729993786,457.2 -3.3514214394,50.6723352766,457.2 -3.348825222,50.67199629,457.2 -3.346174778,50.67199629,457.2 -3.3435785606,50.6723352766,457.2 -3.3411428072,50.6729993786,457.2 -3.338967198999999,50.6739614205,457.2 -3.3371407859,50.675182033,457.2 -3.3357383444,50.6766112617,457.2 -3.3348173154,50.6781906099,457.2 -3.334415448800001,50.6798554304,457.2 -3.3345492511,50.6815375708,457.2 -3.3352133005,50.68316816200001,457.2 -3.3363804602,50.684680439,457.2 -3.3380029813,50.6860124748,457.2 -3.3400144516,50.68710971849999,457.2 -3.3423325129,50.6879272312,457.2 -3.3448622335,50.68843152869999,457.2 -3.3475,50.6886019548,457.2 + + + + +
+ + EGD064A SOUTH WEST COMPLEX + 512016N 0071115W -
511616N 0061643W -
502838N 0060046W -
501752N 0070521W -
502621N 0073603W -
503808N 0074914W -
504705N 0075207W -
505745N 0075205W -
512016N 0071115W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8686888889,50.78467222219999,20116.8 -7.820425,50.6354777778,20116.8 -7.6007361111,50.4391444444,20116.8 -7.0891277778,50.2977472222,20116.8 -6.0128138889,50.4771666667,20116.8 -6.278702777800001,51.2711527778,20116.8 -7.1874361111,51.3376777778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,1524 -7.8681916667,50.9625111111,1524 -7.8686888889,50.78467222219999,1524 -7.820425,50.6354777778,1524 -7.6007361111,50.4391444444,1524 -7.0891277778,50.2977472222,1524 -6.0128138889,50.4771666667,1524 -6.278702777800001,51.2711527778,1524 -7.1874361111,51.3376777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.1874361111,51.3376777778,1524 -7.8681916667,50.9625111111,1524 -7.8681916667,50.9625111111,20116.8 -7.1874361111,51.3376777778,20116.8 -7.1874361111,51.3376777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.8681916667,50.9625111111,1524 -7.8686888889,50.78467222219999,1524 -7.8686888889,50.78467222219999,20116.8 -7.8681916667,50.9625111111,20116.8 -7.8681916667,50.9625111111,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.8686888889,50.78467222219999,1524 -7.820425,50.6354777778,1524 -7.820425,50.6354777778,20116.8 -7.8686888889,50.78467222219999,20116.8 -7.8686888889,50.78467222219999,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.820425,50.6354777778,1524 -7.6007361111,50.4391444444,1524 -7.6007361111,50.4391444444,20116.8 -7.820425,50.6354777778,20116.8 -7.820425,50.6354777778,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.6007361111,50.4391444444,1524 -7.0891277778,50.2977472222,1524 -7.0891277778,50.2977472222,20116.8 -7.6007361111,50.4391444444,20116.8 -7.6007361111,50.4391444444,1524 + + + + + + relativeToGround + + + relativeToGround + + -7.0891277778,50.2977472222,1524 -6.0128138889,50.4771666667,1524 -6.0128138889,50.4771666667,20116.8 -7.0891277778,50.2977472222,20116.8 -7.0891277778,50.2977472222,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.0128138889,50.4771666667,1524 -6.278702777800001,51.2711527778,1524 -6.278702777800001,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -7.1874361111,51.3376777778,1524 -7.1874361111,51.3376777778,20116.8 -6.278702777800001,51.2711527778,20116.8 -6.278702777800001,51.2711527778,1524 + + + + + +
+ + EGD064B SOUTH WEST COMPLEX + 511616N 0061643W -
511207N 0052532W -
510624N 0052510W -
503012N 0054335W -
502838N 0060046W -
511616N 0061643W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,20116.8 -6.0128138889,50.4771666667,20116.8 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.20208055559999,20116.8 -6.278702777800001,51.2711527778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -6.0128138889,50.4771666667,1524 -5.7262777778,50.5032416667,1524 -5.4195055556,51.1065583333,1524 -5.4255305556,51.20208055559999,1524 -6.278702777800001,51.2711527778,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.278702777800001,51.2711527778,1524 -6.0128138889,50.4771666667,1524 -6.0128138889,50.4771666667,20116.8 -6.278702777800001,51.2711527778,20116.8 -6.278702777800001,51.2711527778,1524 + + + + + + relativeToGround + + + relativeToGround + + -6.0128138889,50.4771666667,1524 -5.7262777778,50.5032416667,1524 -5.7262777778,50.5032416667,20116.8 -6.0128138889,50.4771666667,20116.8 -6.0128138889,50.4771666667,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7262777778,50.5032416667,1524 -5.4195055556,51.1065583333,1524 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4195055556,51.1065583333,1524 -5.4255305556,51.20208055559999,1524 -5.4255305556,51.20208055559999,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -6.278702777800001,51.2711527778,1524 -6.278702777800001,51.2711527778,20116.8 -5.4255305556,51.20208055559999,20116.8 -5.4255305556,51.20208055559999,1524 + + + + + +
+ + EGD064C SOUTH WEST COMPLEX + 511207N 0052532W -
511028N 0050621W -
505443N 0043352W -
504712N 0043327W -
504423N 0043914W -
504328N 0043921W -
503012N 0054335W -
510624N 0052510W -
511207N 0052532W
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,20116.8 -5.4195055556,51.1065583333,20116.8 -5.7262777778,50.5032416667,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6538055556,50.7396694444,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5643666667,50.9120277778,20116.8 -5.1057833333,51.1745361111,20116.8 -5.4255305556,51.20208055559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -5.4195055556,51.1065583333,1524 -5.7262777778,50.5032416667,1524 -4.6557722222,50.7243333333,1524 -4.6538055556,50.7396694444,1524 -4.5574972222,50.7866166667,1524 -4.5643666667,50.9120277778,1524 -5.1057833333,51.1745361111,1524 -5.4255305556,51.20208055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4255305556,51.20208055559999,1524 -5.4195055556,51.1065583333,1524 -5.4195055556,51.1065583333,20116.8 -5.4255305556,51.20208055559999,20116.8 -5.4255305556,51.20208055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.4195055556,51.1065583333,1524 -5.7262777778,50.5032416667,1524 -5.7262777778,50.5032416667,20116.8 -5.4195055556,51.1065583333,20116.8 -5.4195055556,51.1065583333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7262777778,50.5032416667,1524 -4.6557722222,50.7243333333,1524 -4.6557722222,50.7243333333,20116.8 -5.7262777778,50.5032416667,20116.8 -5.7262777778,50.5032416667,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.6557722222,50.7243333333,1524 -4.6538055556,50.7396694444,1524 -4.6538055556,50.7396694444,20116.8 -4.6557722222,50.7243333333,20116.8 -4.6557722222,50.7243333333,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.6538055556,50.7396694444,1524 -4.5574972222,50.7866166667,1524 -4.5574972222,50.7866166667,20116.8 -4.6538055556,50.7396694444,20116.8 -4.6538055556,50.7396694444,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.5574972222,50.7866166667,1524 -4.5643666667,50.9120277778,1524 -4.5643666667,50.9120277778,20116.8 -4.5574972222,50.7866166667,20116.8 -4.5574972222,50.7866166667,1524 + + + + + + relativeToGround + + + relativeToGround + + -4.5643666667,50.9120277778,1524 -5.1057833333,51.1745361111,1524 -5.1057833333,51.1745361111,20116.8 -4.5643666667,50.9120277778,20116.8 -4.5643666667,50.9120277778,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.1057833333,51.1745361111,1524 -5.4255305556,51.20208055559999,1524 -5.4255305556,51.20208055559999,20116.8 -5.1057833333,51.1745361111,20116.8 -5.1057833333,51.1745361111,1524 + + + + + +
+ + EGD110 BRAUNTON BURROWS + 510602N 0041529W -
510606N 0041203W -
510500N 0041200W -
510458N 0041315W -
510516N 0041344W -
510514N 0041527W -
510602N 0041529W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 07870-377646 or 01395-277891.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.2580305556,51.1005694444,609.6 -4.2573722222,51.0870916667,609.6 -4.2288388889,51.0876416667,609.6 -4.2207555556,51.0828472222,609.6 -4.2000694444,51.08323888889999,609.6 -4.2009444444,51.10166111110001,609.6 -4.2580305556,51.1005694444,609.6 + + + + +
+ + EGD113A CASTLEMARTIN + 513937N 0051830W following the line of latitude to -
513937N 0050443W -
513906N 0050320W -
513130N 0050530W -
512900N 0050330W following the line of latitude to -
512900N 0045432W -
512430N 0050220W thence clockwise by the arc of a circle radius 18.1 NM centred on 514213N 0045647W to
513610N 0052408W -
513937N 0051830W
Upper limit: 40000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.

Remarks: SI 1986/1834.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3083333333,51.6602777778,12192 -5.4022222222,51.6027777778,12192 -5.3963665818,51.5933780264,12192 -5.3901403276,51.5840734082,12192 -5.3834198158,51.5749035623,12192 -5.3762128249,51.5658786995,12192 -5.3685276609,51.5570088636,12192 -5.3603731468,51.5483039199,12192 -5.351758612,51.53977354500001,12192 -5.342693881,51.53142721590001,12192 -5.3331892616,51.5232742004,12192 -5.3232555331,51.5153235465,12192 -5.3129039336,51.5075840732,12192 -5.3021461467,51.5000643609,12192 -5.2909942889,51.4927727422,12192 -5.2794608951,51.4857172931,12192 -5.2675589047,51.4789058244,12192 -5.2553016477,51.4723458735,12192 -5.2427028289,51.4660446964,12192 -5.2297765136,51.4600092598,12192 -5.216537112,51.454246234,12192 -5.2029993633,51.448761986,12192 -5.1891783197,51.4435625724,12192 -5.1750893305,51.4386537333,12192 -5.1607480254,51.4340408864,12192 -5.1461702976,51.42972912110001,12192 -5.1313722874,51.4257231931,12192 -5.1163703645,51.4220275198,12192 -5.1011811112,51.4186461753,12192 -5.0858213045,51.4155828866,12192 -5.070307899,51.4128410291,12192 -5.0546580086,51.4104236237,12192 -5.0388888889,51.40833333329999,12192 -4.9088888889,51.48333333330001,12192 -4.9836111111,51.48333333330001,12192 -5.0583333333,51.48333333330001,12192 -5.0916666667,51.525,12192 -5.0555555556,51.6516666667,12192 -5.0786111111,51.6602777778,12192 -5.1934722222,51.6602777778,12192 -5.3083333333,51.6602777778,12192 + + + + +
+ + EGD113B CASTLEMARTIN + 513906N 0050320W thence clockwise by the arc of a circle radius 6.6 NM centred on 513230N 0050400W to
513618N 0045520W -
513618N 0045332W -
513230N 0044830W -
512900N 0045432W -
512900N 0050330W -
513130N 0050530W -
513906N 0050320W
Upper limit: 45000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01646-662496.

Remarks: SI 1986/1834.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0555555556,51.6516666667,13716 -5.0916666667,51.525,13716 -5.0583333333,51.48333333330001,13716 -4.9088888889,51.48333333330001,13716 -4.8083333333,51.5416666667,13716 -4.8922222222,51.605,13716 -4.9222222222,51.605,13716 -4.9279167223,51.61003039919999,13716 -4.9342578797,51.614754824,13716 -4.9410141992,51.6192510473,13716 -4.9481646133,51.62350497,13716 -4.9556867999,51.6275032486,13716 -4.9635572517,51.63123333839999,13716 -4.9717513502,51.63468353299999,13716 -4.9802434429,51.6378430019,13716 -4.9890069249,51.6407018251,13716 -4.9980143228,51.6432510247,13716 -5.0072373821,51.6454825939,13716 -5.0166471575,51.6473895223,13716 -5.0262141049,51.64896581859999,13716 -5.0359081761,51.65020652960001,13716 -5.0456989152,51.6511077564,13716 -5.0555555556,51.6516666667,13716 + + + + +
+ + EGD115A MANORBIER + 513815N 0045012W thence clockwise by the arc of a circle radius 2 NM centred on 513815N 0044700W to
513815N 0044348W -
513815N 0045012W
Upper limit: 27000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.

Remarks: SI 1941/158.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8366666667,51.6375,8229.6 -4.73,51.6375,8229.6 -4.7302715604,51.6408567001,8229.6 -4.7310874734,51.6441790898,8229.6 -4.7324394857,51.6474330816,8229.6 -4.734313836,51.65058528269999,8229.6 -4.7366913916,51.6536033378,8229.6 -4.7395478412,51.6564562626,8229.6 -4.7428539406,51.6591147623,8229.6 -4.746575811,51.66155153370001,8229.6 -4.7506752849,51.6637415465,8229.6 -4.7551102976,51.6656623018,8229.6 -4.7598353191,51.66729406410001,8229.6 -4.7648018228,51.6686200655,8229.6 -4.7699587861,51.6696266787,8229.6 -4.7752532169,51.6703035578,8229.6 -4.7806307011,51.6706437457,8229.6 -4.7860359656,51.6706437457,8229.6 -4.7914134498,51.6703035578,8229.6 -4.7967078805,51.6696266787,8229.6 -4.8018648438,51.6686200655,8229.6 -4.8068313476,51.66729406410001,8229.6 -4.811556369,51.6656623018,8229.6 -4.8159913818,51.6637415465,8229.6 -4.8200908557,51.66155153370001,8229.6 -4.8238127261,51.6591147623,8229.6 -4.8271188255,51.6564562626,8229.6 -4.829975275,51.6536033378,8229.6 -4.8323528307,51.65058528269999,8229.6 -4.834227181,51.6474330816,8229.6 -4.8355791933,51.6441790898,8229.6 -4.8363951063,51.6408567001,8229.6 -4.8366666667,51.6375,8229.6 + + + + +
+ + EGD115B MANORBIER + 513815N 0045012W -
513815N 0044348W -
513345N 0043019W thence clockwise by the arc of a circle radius 11.34 NM centred on 513815N 0044700W to
513208N 0050218W -
513815N 0045012W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: As detailed in activation NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01834-871282.

Remarks: SI 1941/158.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8366666667,51.6375,15240 -5.0383333333,51.5355555556,15240 -5.0309417218,51.5288043613,15240 -5.0231463892,51.5222339864,15240 -5.0149045172,51.51587978300001,15240 -5.0062316321,51.509753581,15240 -4.9971440429,51.5038667816,15240 -4.9876588105,51.49823033580001,15240 -4.9777937157,51.4928547252,15240 -4.9675672259,51.4877499426,15240 -4.9569984611,51.48292547439999,15240 -4.946107158,51.478390283,15240 -4.934913634,51.4741527909,15240 -4.9234387502,51.4702208656,15240 -4.9117038729,51.4666018052,15240 -4.8997308346,51.4633023255,15240 -4.8875418953,51.460328548,15240 -4.8751597012,51.4576859887,15240 -4.8626072445,51.4553795484,15240 -4.849907822,51.4534135038,15240 -4.8370849928,51.4517915,15240 -4.8241625367,51.4505165438,15240 -4.8111644114,51.4495909985,15240 -4.7981147096,51.4490165796,15240 -4.785037616,51.4487943517,15240 -4.7719573642,51.4489247268,15240 -4.7588981934,51.449407463,15240 -4.7458843053,51.4502416659,15240 -4.7329398206,51.45142578910001,15240 -4.7200887363,51.4529576379,15240 -4.7073548826,51.4548343726,15240 -4.6947618804,51.4570525138,15240 -4.6823330987,51.4596079487,15240 -4.6700916132,51.46249593820001,15240 -4.6580601642,51.46571112580001,15240 -4.646261116,51.46924754669999,15240 -4.6347164165,51.4730986389,15240 -4.6234475573,51.4772572546,15240 -4.6124755347,51.48171567349999,15240 -4.6018208114,51.4864656162,15240 -4.5915032789,51.4914982594,15240 -4.5815422215,51.4968042517,15240 -4.5719562797,51.5023737305,15240 -4.5627634166,51.50819633990001,15240 -4.5539808837,51.514261249,15240 -4.5456251891,51.52055717219999,15240 -4.5377120657,51.5270723892,15240 -4.5302564419,51.53379476650001,15240 -4.5232724124,51.5407117792,15240 -4.5167732117,51.5478105344,15240 -4.5107711877,51.5550777941,15240 -4.5052777778,51.5625,15240 -4.73,51.6375,15240 -4.8366666667,51.6375,15240 + + + + +
+ + EGD117 PENDINE + 513510N 0042400W -
513629N 0043752W -
513958N 0043743W -
514515N 0043300W -
514524N 0042517W -
514445N 0042400W -
513510N 0042400W
Upper limit: 27000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 23,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 27,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information: Range Control, Tel: 01994-452240.

Remarks: SI 1973/1627. UAS BVLOS will not be conducted above 10,000 FT ALT.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4,51.5861111111,8229.6 -4.4,51.7458333333,8229.6 -4.4213888889,51.7566666667,8229.6 -4.55,51.7541666667,8229.6 -4.6286111111,51.66611111110001,8229.6 -4.6311111111,51.6080555556,8229.6 -4.4,51.5861111111,8229.6 + + + + +
+ + EGD118 PEMBREY + 514625N 0042400W thence clockwise by the arc of a circle radius 3.5 NM centred on 514313N 0042144W to
514001N 0042400W -
514625N 0042400W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 12,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS / SUAAIS: Pembrey Range on 122.750 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01554-892205.

Remarks: Associated aircraft operations outside area boundary; 122.750 MHz is a common frequency also used by Holbeach and Donna Nook AWRs. Ensure crossing clearance request is specific to Pembrey AWR. UAS BVLOS will not be conducted above 9000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4,51.7736111111,7010.400000000001 -4.4,51.6669444444,7010.400000000001 -4.3932089918,51.66529097230001,7010.400000000001 -4.386237853,51.6639604701,7010.400000000001 -4.3791217654,51.6629707362,7010.400000000001 -4.3719036854,51.6623277443,7010.400000000001 -4.3646271782,51.6620353749,7010.400000000001 -4.3573361576,51.6620953927,7010.400000000001 -4.3500746236,51.66250743539999,7010.400000000001 -4.3428864007,51.6632690162,7010.400000000001 -4.3358148759,51.6643755387,7010.400000000001 -4.3289027398,51.6658203243,7010.400000000001 -4.3221917315,51.6675946518,7010.400000000001 -4.3157223893,51.6696878099,7010.400000000001 -4.3095338075,51.67208716079999,7010.400000000001 -4.3036634025,51.674778216,7010.400000000001 -4.2981466874,51.67774472279999,7010.400000000001 -4.2930170582,51.68096876169999,7010.400000000001 -4.2883055923,51.6844308533,7010.400000000001 -4.2840408602,51.6881100757,7010.400000000001 -4.2802487514,51.6919841894,7010.400000000001 -4.2769523168,51.6960297713,7010.400000000001 -4.2741716265,51.700222355,7010.400000000001 -4.2719236467,51.7045365786,7010.400000000001 -4.2702221333,51.7089463366,7010.400000000001 -4.2690775454,51.7134249384,7010.400000000001 -4.2684969787,51.71794526830001,7010.400000000001 -4.268484118,51.7224799502,7010.400000000001 -4.2690392114,51.7270015129,7010.400000000001 -4.2701590641,51.7314825564,7010.400000000001 -4.2718370543,51.7358959184,7010.400000000001 -4.274063169,51.7402148389,7010.400000000001 -4.2768240608,51.7444131231,7010.400000000001 -4.2801031259,51.7484653009,7010.400000000001 -4.2838806013,51.7523467816,7010.400000000001 -4.2881336823,51.7560340046,7010.400000000001 -4.2928366585,51.75950458270001,7010.400000000001 -4.2979610682,51.762737439,7010.400000000001 -4.3034758704,51.7657129363,7010.400000000001 -4.3093476325,51.76841299660001,7010.400000000001 -4.3155407334,51.7708212126,7010.400000000001 -4.3220175804,51.7729229477,7010.400000000001 -4.328738839,51.7747054264,7010.400000000001 -4.3356636736,51.7761578122,7010.400000000001 -4.3427499972,51.77727127450001,7010.400000000001 -4.3499547303,51.778039043,7010.400000000001 -4.3572340651,51.7784564488,7010.400000000001 -4.364543735,51.7785209536,7010.400000000001 -4.3718392867,51.7782321652,7010.400000000001 -4.3790763538,51.7775918398,7010.400000000001 -4.3862109299,51.7766038711,7010.400000000001 -4.3931996384,51.7752742668,7010.400000000001 -4.4,51.7736111111,7010.400000000001 + + + + +
+ + EGD119 BRIDGWATER BAY + A circle, 4 NM radius, centred at 511224N 0031353W
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Yeovilton APP on 127.350 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information: RNAS Yeovilton Air Operations, Tel: 01935-455497. Booking: RNAS Yeovilton Air Weapons Supply, Tel: 01935-455449. Range Tower when manned, Tel: 01278-741337.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2313888889,51.2732537142,1524 -3.2391376971,51.27307582360001,1524 -3.2468449835,51.27254310509999,1524 -3.254469451499999,51.27165841290001,1524 -3.2619702543,51.2704264874,1524 -3.2693072156,51.26885392860001,1524 -3.2764410482,51.266949161,1524 -3.2833335658,51.2647223876,1524 -3.2899478902,51.2621855343,1524 -3.2962486495,51.2593521862,1524 -3.3022021691,51.2562375131,1524 -3.3077766525,51.2528581878,1524 -3.3129423514,51.24923229629999,1524 -3.3176717247,51.2453792395,1524 -3.321939585,51.241319629,1524 -3.3257232319,51.2370751757,1524 -3.3290025716,51.2326685731,1524 -3.3317602224,51.2281233748,1524 -3.333981604299999,51.2234638686,1524 -3.335655014599999,51.2187149454,1524 -3.336771687,51.2139019661,1524 -3.3373258345,51.209050626,1524 -3.337314677,51.2041868169,1524 -3.336738452300001,51.1993364891,1524 -3.3356004111,51.1945255131,1524 -3.3339067956,51.1897795412,1524 -3.331666803,51.1851238715,1524 -3.3288925326,51.1805833133,1524 -3.3255989185,51.17618205519999,1524 -3.3218036468,51.1719435371,1524 -3.317527058900001,51.1678903259,1524 -3.3127920413,51.16404399629999,1524 -3.3076239017,51.1604250162,1524 -3.3020502333,51.15705263949999,1524 -3.2961007668,51.15394480390001,1524 -3.2898072125,51.1511180366,1524 -3.283203091599999,51.14858736719999,1524 -3.276323558100001,51.14636624869999,1524 -3.2692052139,51.1444664867,1524 -3.2618859148,51.1428981776,1524 -3.254404571999999,51.1416696551,1524 -3.2468009466,51.1407874469,1524 -3.2391154415,51.14025624010001,1524 -3.2313888889,51.14007885709999,1524 -3.2236623363,51.14025624010001,1524 -3.2159768312,51.1407874469,1524 -3.2083732058,51.1416696551,1524 -3.200891862899999,51.1428981776,1524 -3.1935725639,51.1444664867,1524 -3.1864542197,51.14636624869999,1524 -3.1795746862,51.14858736719999,1524 -3.1729705652,51.1511180366,1524 -3.166677011,51.15394480390001,1524 -3.1607275445,51.15705263949999,1524 -3.155153876,51.1604250162,1524 -3.149985736500001,51.16404399629999,1524 -3.1452507189,51.1678903259,1524 -3.140974131000001,51.1719435371,1524 -3.1371788593,51.17618205519999,1524 -3.1338852452,51.1805833133,1524 -3.1311109748,51.1851238715,1524 -3.1288709822,51.1897795412,1524 -3.1271773667,51.1945255131,1524 -3.1260393255,51.1993364891,1524 -3.1254631008,51.2041868169,1524 -3.125451943299999,51.209050626,1524 -3.1260060908,51.2139019661,1524 -3.1271227631,51.2187149454,1524 -3.1287961735,51.2234638686,1524 -3.1310175554,51.2281233748,1524 -3.1337752061,51.2326685731,1524 -3.1370545459,51.2370751757,1524 -3.1408381928,51.241319629,1524 -3.145106053,51.2453792395,1524 -3.1498354263,51.24923229629999,1524 -3.1550011252,51.2528581878,1524 -3.1605756087,51.2562375131,1524 -3.1665291283,51.2593521862,1524 -3.1728298876,51.2621855343,1524 -3.1794442119,51.2647223876,1524 -3.1863367296,51.266949161,1524 -3.1934705622,51.26885392860001,1524 -3.2008075235,51.2704264874,1524 -3.2083083262,51.27165841290001,1524 -3.2159327943,51.27254310509999,1524 -3.2236400807,51.27307582360001,1524 -3.2313888889,51.2732537142,1524 + + + + +
+ + EGD120 BOSCOMBE DOWN + 511052N 0014802W -
511059N 0014641W -
511044N 0014308W -
511105N 0014228W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510844N 0014110W -
510801N 0014248W -
510730N 0014248W -
510646N 0014409W -
510746N 0014819W thence clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to -
511052N 0014802W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: This Danger Area is contained within the extant Boscombe Down ATZ; all regulations associated with flight within an ATZ remain applicable. Upper limit is expressed by reference to height, based on Boscombe Down QFE (identical to ATZ upper limit).

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8005555556,51.18111111110001,762 -1.804205638,51.1781799843,762 -1.807520014,51.1751003506,762 -1.810383437,51.1718469736,762 -1.8127731156,51.1684458589,762 -1.8146700582,51.1649241872,762 -1.8160592224,51.1613100965,762 -1.8169296313,51.1576324567,762 -1.8172744577,51.1539206381,762 -1.817091075,51.15020427749999,762 -1.8163810737,51.1465130403,762 -1.815150245,51.1428763847,762 -1.8134085306,51.13932332660001,762 -1.8111699394,51.1358822079,762 -1.8084524327,51.1325804719,762 -1.8052777778,51.1294444444,762 -1.7358333333,51.1127777778,762 -1.7133333333,51.125,762 -1.7133333333,51.1336111111,762 -1.6861111111,51.14555555559999,762 -1.6853632646,51.1491417891,762 -1.6850302822,51.1527499945,762 -1.6851969823,51.1563627495,762 -1.6858622209,51.15995273230001,762 -1.6870210811,51.16349278709999,762 -1.6886649068,51.1669561299,762 -1.6907813654,51.1703165508,762 -1.6933545375,51.1735486135,762 -1.6963650348,51.17662784809999,762 -1.6997901449,51.17953093689999,762 -1.7036040013,51.18223589200001,762 -1.7077777778,51.1847222222,762 -1.7188888889,51.1788888889,762 -1.7780555556,51.1830555556,762 -1.8005555556,51.18111111110001,762 + + + + +
+ + EGD122A WESSEX WEST + 511329N 0021149W -
511106N 0020713W -
511006N 0015702W -
510125N 0015702W -
505938N 0020714W -
510120N 0021149W -
511329N 0021149W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122A and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.02222222220001,4876.8 -2.1205555556,50.9938888889,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -2.1202777778,51.185,4876.8 -2.1969444444,51.2247222222,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.02222222220001,2438.4 -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.02222222220001,2438.4 -2.1969444444,51.02222222220001,4876.8 -2.1969444444,51.2247222222,4876.8 -2.1969444444,51.2247222222,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1969444444,51.02222222220001,2438.4 -2.1205555556,50.9938888889,2438.4 -2.1205555556,50.9938888889,4876.8 -2.1969444444,51.02222222220001,4876.8 -2.1969444444,51.02222222220001,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1205555556,50.9938888889,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -2.1205555556,50.9938888889,4876.8 -2.1205555556,50.9938888889,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.1683333333,2438.4 -2.1202777778,51.185,2438.4 -2.1202777778,51.185,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -2.1202777778,51.185,2438.4 -2.1969444444,51.2247222222,2438.4 -2.1969444444,51.2247222222,4876.8 -2.1202777778,51.185,4876.8 -2.1202777778,51.185,2438.4 + + + + + +
+ + EGD122B WESSEX CENTRAL + 511059N 0014641W -
511044N 0014308W -
510357N 0014230W -
510125N 0015702W -
511006N 0015702W -
511059N 0014641W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122B and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7780555556,51.1830555556,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7780555556,51.1830555556,2438.4 -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.1683333333,4876.8 -1.7780555556,51.1830555556,4876.8 -1.7780555556,51.1830555556,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.1683333333,2438.4 -1.9505555556,51.0236111111,2438.4 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.1683333333,4876.8 -1.9505555556,51.1683333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.9505555556,51.0236111111,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.9505555556,51.0236111111,4876.8 -1.9505555556,51.0236111111,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7083333333,51.0658333333,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7188888889,51.1788888889,2438.4 -1.7780555556,51.1830555556,2438.4 -1.7780555556,51.1830555556,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + +
+ + EGD122C WESSEX EAST + 511335N 0013725W -
511236N 0013044W -
510527N 0013342W -
510357N 0014230W -
511044N 0014308W -
511233N 0013942W -
511247N 0013759W -
511335N 0013725W
Upper limit: FL160
Lower limit: FL80
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone 126.700 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD122C and will be provided with a Deconfliction Service. Pilots who are unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,4876.8 -1.6330555556,51.21305555559999,4876.8 -1.6616666667,51.2091666667,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7083333333,51.0658333333,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5122222222,51.21000000000001,4876.8 -1.6236111111,51.22638888889999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,2438.4 -1.6330555556,51.21305555559999,2438.4 -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21000000000001,2438.4 -1.6236111111,51.22638888889999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6236111111,51.22638888889999,2438.4 -1.6330555556,51.21305555559999,2438.4 -1.6330555556,51.21305555559999,4876.8 -1.6236111111,51.22638888889999,4876.8 -1.6236111111,51.22638888889999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6330555556,51.21305555559999,2438.4 -1.6616666667,51.2091666667,2438.4 -1.6616666667,51.2091666667,4876.8 -1.6330555556,51.21305555559999,4876.8 -1.6330555556,51.21305555559999,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.6616666667,51.2091666667,2438.4 -1.7188888889,51.1788888889,2438.4 -1.7188888889,51.1788888889,4876.8 -1.6616666667,51.2091666667,4876.8 -1.6616666667,51.2091666667,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7188888889,51.1788888889,2438.4 -1.7083333333,51.0658333333,2438.4 -1.7083333333,51.0658333333,4876.8 -1.7188888889,51.1788888889,4876.8 -1.7188888889,51.1788888889,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.7083333333,51.0658333333,2438.4 -1.5616666667,51.0908333333,2438.4 -1.5616666667,51.0908333333,4876.8 -1.7083333333,51.0658333333,4876.8 -1.7083333333,51.0658333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.5616666667,51.0908333333,2438.4 -1.5122222222,51.21000000000001,2438.4 -1.5122222222,51.21000000000001,4876.8 -1.5616666667,51.0908333333,4876.8 -1.5616666667,51.0908333333,2438.4 + + + + + + relativeToGround + + + relativeToGround + + -1.5122222222,51.21000000000001,2438.4 -1.6236111111,51.22638888889999,2438.4 -1.6236111111,51.22638888889999,4876.8 -1.5122222222,51.21000000000001,4876.8 -1.5122222222,51.21000000000001,2438.4 + + + + + +
+ + EGD123 IMBER + 511724N 0020107W -
511339N 0015746W -
511348N 0015705W -
511023N 0015325W -
511006N 0015702W -
511106N 0020713W -
511329N 0021149W -
511516N 0020939W -
511705N 0020312W -
511724N 0020107W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 3000 FT ALT H24.

Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730 when open.

Remarks: SI 1963/1293, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0186111111,51.29,15240 -2.0533333333,51.2847222222,15240 -2.1608333333,51.25444444439999,15240 -2.1969444444,51.2247222222,15240 -2.1202777778,51.185,15240 -1.9505555556,51.1683333333,15240 -1.8902777778,51.1730555556,15240 -1.9513888889,51.23,15240 -1.9627777778,51.2275,15240 -2.0186111111,51.29,15240 + + + + +
+ + EGD124 LAVINGTON + A circle, 1.5 NM radius, centred at 511527N 0015812W
Upper limit: UNL
Lower limit: SFC
Class: AMC Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710.

Remarks: SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.97,51.282470014,30449.52 -1.9747091708,51.2822946576,30449.52 -1.9793521288,51.2817710539,30449.52 -1.9838635968,51.2809065647,30449.52 -1.988180155,51.2797133442,30449.52 -1.992241136,51.2782081673,30449.52 -1.995989481,51.2764121923,30449.52 -1.9993725434,51.2743506631,30449.52 -2.0023428293,51.2720525523,30449.52 -2.0048586647,51.2695501529,30449.52 -2.0068847788,51.266878623,30449.52 -2.008392797,51.264075491,30449.52 -2.009361635,51.26118012690001,30449.52 -2.0097777904,51.2582331885,30449.52 -2.0096355267,51.2552760504,30449.52 -2.0089369474,51.2523502221,30449.52 -2.0076919612,51.2494967662,30449.52 -2.005918137,51.246755722,30449.52 -2.0036404518,51.2441655445,30449.52 -2.0008909363,51.24176256610001,30449.52 -1.9977082216,51.23958048779999,30449.52 -1.9941369955,51.237649908,30449.52 -1.9902273742,51.235997895,30449.52 -1.9860342001,51.2346476088,30449.52 -1.9816162739,51.2336179772,30449.52 -1.9770355326,51.2329234326,30449.52 -1.972356185,51.23257370950001,30449.52 -1.967643815,51.23257370950001,30449.52 -1.9629644674,51.2329234326,30449.52 -1.9583837261,51.2336179772,30449.52 -1.9539657999,51.2346476088,30449.52 -1.9497726258,51.235997895,30449.52 -1.9458630045,51.237649908,30449.52 -1.9422917784,51.23958048779999,30449.52 -1.9391090637,51.24176256610001,30449.52 -1.9363595482,51.2441655445,30449.52 -1.934081863,51.246755722,30449.52 -1.9323080388,51.2494967662,30449.52 -1.9310630526,51.2523502221,30449.52 -1.9303644733,51.2552760504,30449.52 -1.9302222096,51.2582331885,30449.52 -1.930638365,51.26118012690001,30449.52 -1.931607203,51.264075491,30449.52 -1.9331152212,51.266878623,30449.52 -1.9351413353,51.2695501529,30449.52 -1.9376571707,51.2720525523,30449.52 -1.9406274566,51.2743506631,30449.52 -1.944010519,51.2764121923,30449.52 -1.947758864,51.2782081673,30449.52 -1.951819845,51.2797133442,30449.52 -1.9561364032,51.2809065647,30449.52 -1.9606478712,51.2817710539,30449.52 -1.9652908292,51.2822946576,30449.52 -1.97,51.282470014,30449.52 + + + + +
+ + EGD125 LARKHILL + 511828N 0015004W -
511059N 0014641W -
511023N 0015325W -
511348N 0015705W -
511339N 0015746W -
511724N 0020107W -
511807N 0015635W -
511828N 0015004W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 3000 FT ALT H24.

Vertical Limit 23000 FT ALT Mon-Thu 0800-2359 (0700-2300), Fri 0800-1730 (0700-1630).

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft Systems (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 674730.

Remarks: SI 1965/1327, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8344444444,51.3077777778,15240 -1.9430555556,51.3019444444,15240 -2.0186111111,51.29,15240 -1.9627777778,51.2275,15240 -1.9513888889,51.23,15240 -1.8902777778,51.1730555556,15240 -1.7780555556,51.1830555556,15240 -1.8344444444,51.3077777778,15240 + + + + +
+ + EGD126 BULFORD + 511621N 0013746W -
511525N 0013606W -
511247N 0013759W -
511233N 0013942W -
511044N 0014308W -
511059N 0014641W -
511351N 0014759W thence clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to
511354N 0014225W -
511621N 0013746W
Upper limit: FL90
Lower limit: SFC
Class: AMC Manageable.

Vertical Limit 1400 FT ALT H24.

Vertical Limit OCNL notified up to FL 90 by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710 or 01980-674730 or Boscombe Down ATC, Tel: 01980-663246.

Remarks: SI 1970/1282, SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6294444444,51.27250000000001,2743.2 -1.7069444444,51.2316666667,2743.2 -1.715059155,51.2334964065,2743.2 -1.7234325199,51.2348000136,2743.2 -1.7319235049,51.2357586607,2743.2 -1.7404960327,51.2363682739,2743.2 -1.7491136738,51.2366262626,2743.2 -1.757739804,51.2365315304,2743.2 -1.7663377624,51.2360844798,2743.2 -1.7748710099,51.23528701079999,2743.2 -1.7833032865,51.2341425123,2743.2 -1.7915987684,51.2326558475,2743.2 -1.7997222222,51.2308333333,2743.2 -1.7780555556,51.1830555556,2743.2 -1.7188888889,51.1788888889,2743.2 -1.6616666667,51.2091666667,2743.2 -1.6330555556,51.21305555559999,2743.2 -1.6016666667,51.25694444440001,2743.2 -1.6294444444,51.27250000000001,2743.2 + + + + +
+ + EGD127 PORTON + 510552N 0014315W -
510632N 0014435W -
510730N 0014248W -
510801N 0014248W -
511012N 0013750W -
510752N 0013650W -
510703N 0013843W -
510552N 0014315W
Upper limit: 12000 FT MSL
Lower limit: SFC
Class: Vertical Limits:
Upper Limit: ALT 12000 0600-1800 (0500-1700).
Upper Limit: ALT 8000 (OCNL notified to ALT 12000) 1800-0600 (1700-0500).

Activity: Para Dropping / Ordnance, Munitions and Explosives / Electronic/optical hazards / Unmanned Aircraft System (VLOS).

Service: SUACS / SUAAIS: Boscombe Down Zone on 126.700 MHz when open; at other times London Information on 124.750 MHz.

Contact: Pre-flight information: Boscombe Down ATC, Tel: 01980-663246.

Remarks: SI 1977/1611.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7208333333,51.0977777778,3657.6 -1.6452777778,51.1175,3657.6 -1.6138888889,51.1311111111,3657.6 -1.6305555556,51.17,3657.6 -1.7133333333,51.1336111111,3657.6 -1.7133333333,51.125,3657.6 -1.7430555556,51.10888888889999,3657.6 -1.7208333333,51.0977777778,3657.6 + + + + +
+ + EGD128 EVERLEIGH + 511852N 0014215W -
511621N 0013746W -
511354N 0014225W thence anti-clockwise by the arc of a circle radius 5 NM centred on 510912N 0014504W to
511351N 0014759W -
511828N 0015004W -
511852N 0014215W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC Manageable

Vertical Limit 1400 FT ALT H24

Vertical Limit OCNL notified to altitudes up to 50000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz when open; at other times SUAAIS via London Information on 124.750 MHz.

Contact: Pre-flight information: Salisbury Operations, Tel: 01980-674710 or 674730.

Remarks: SI 1981/1882.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7041666667,51.3144444444,15240 -1.8344444444,51.3077777778,15240 -1.7997222222,51.2308333333,15240 -1.7915023174,51.2324672241,15240 -1.7832265947,51.2339503473,15240 -1.774814405,51.2350921193,15240 -1.7663014863,51.2358876884,15240 -1.7577240116,51.2363336739,15240 -1.7491184326,51.2364281804,15240 -1.7405213223,51.2361708064,15240 -1.7319692174,51.2355626455,15240 -1.7234984599,51.2346062823,15240 -1.7151450407,51.2333057807,15240 -1.7069444444,51.2316666667,15240 -1.6294444444,51.27250000000001,15240 -1.7041666667,51.3144444444,15240 + + + + +
+ + EGD129 WESTON-ON-THE-GREEN + A circle, 2 NM radius, centred at 515246N 0011320W
Upper limit: FL120
Lower limit: SFC
Class: Activity: Para Dropping.

Service: SUAAIS: Brize Zone on 119.000 MHz. SUACS: Oxford Approach on 125.090 MHz.

Contact: Pre-flight information / Booking: Brize Norton, Tel: 01993-895147.

Remarks: Parachuting activity up to FL 135 may be conducted with London Control (Swanwick) permission. Regular activity SR-SS to FL 85 described in ENR 5.5.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2222222222,51.9127342248,3657.599999999999 -1.2277568724,51.9125576553,3657.599999999999 -1.2332327248,51.9120298224,3657.599999999999 -1.2385916105,51.91115633339999,3657.599999999999 -1.2437766112,51.9099464672,3657.599999999999 -1.2487326672,51.908413075,3657.599999999999 -1.2534071653,51.9065724429,3657.599999999999 -1.2577504999,51.9044441182,3657.599999999999 -1.2617166009,51.9020507004,3657.599999999999 -1.2652634235,51.8994176001,3657.599999999999 -1.268353394,51.89657276789999,3657.599999999999 -1.270953807,51.8935463967,3657.599999999999 -1.2730371699,51.8903705996,3657.599999999999 -1.2745814917,51.8870790687,3657.599999999999 -1.2755705115,51.8837067162,3657.599999999999 -1.2759938668,51.88028930390001,3657.599999999999 -1.2758471977,51.8768630632,3657.599999999999 -1.2751321884,51.8734643111,3657.599999999999 -1.2738565432,51.870129065,3657.599999999999 -1.2720338997,51.8668926615,3657.599999999999 -1.2696836797,51.8637893825,3657.599999999999 -1.2668308788,51.86085209309999,3657.599999999999 -1.2635057979,51.8581118942,3657.599999999999 -1.2597437196,51.8555977944,3657.599999999999 -1.2555845326,51.85333640429999,3657.599999999999 -1.2510723085,51.8513516557,3657.599999999999 -1.2462548354,51.84966455000001,3657.599999999999 -1.2411831132,51.8482929371,3657.599999999999 -1.2359108155,51.8472513271,3657.599999999999 -1.2304937247,51.8465507384,3657.599999999999 -1.2249891449,51.8461985817,3657.599999999999 -1.2194552996,51.8461985817,3657.599999999999 -1.2139507197,51.8465507384,3657.599999999999 -1.2085336289,51.8472513271,3657.599999999999 -1.2032613312,51.8482929371,3657.599999999999 -1.198189609,51.84966455000001,3657.599999999999 -1.193372136,51.8513516557,3657.599999999999 -1.1888599119,51.85333640429999,3657.599999999999 -1.1847007249,51.8555977944,3657.599999999999 -1.1809386465,51.8581118942,3657.599999999999 -1.1776135656,51.86085209309999,3657.599999999999 -1.1747607647,51.8637893825,3657.599999999999 -1.1724105447,51.8668926615,3657.599999999999 -1.1705879013,51.870129065,3657.599999999999 -1.169312256,51.8734643111,3657.599999999999 -1.1685972467,51.8768630632,3657.599999999999 -1.1684505777,51.88028930390001,3657.599999999999 -1.1688739329,51.8837067162,3657.599999999999 -1.1698629527,51.8870790687,3657.599999999999 -1.1714072745,51.8903705996,3657.599999999999 -1.1734906375,51.8935463967,3657.599999999999 -1.1760910505,51.89657276789999,3657.599999999999 -1.179181021,51.8994176001,3657.599999999999 -1.1827278436,51.9020507004,3657.599999999999 -1.1866939445,51.9044441182,3657.599999999999 -1.1910372791,51.9065724429,3657.599999999999 -1.1957117772,51.908413075,3657.599999999999 -1.2006678332,51.9099464672,3657.599999999999 -1.2058528339,51.91115633339999,3657.599999999999 -1.2112117197,51.9120298224,3657.599999999999 -1.2166875721,51.9125576553,3657.599999999999 -1.2222222222,51.9127342248,3657.599999999999 + + + + +
+ + EGD130 LONGMOOR + 510559N 0005213W -
510541N 0004938W -
510446N 0004940W -
510426N 0005301W -
510559N 0005213W
Upper limit: 2300 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1800 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2300 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01420-483405.

Remarks: SI 1982/1179.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8702777778,51.0997222222,701.0400000000001 -0.8836111111,51.0738888889,701.0400000000001 -0.8277777777999999,51.0794444444,701.0400000000001 -0.8272222222000001,51.0947222222,701.0400000000001 -0.8702777778,51.0997222222,701.0400000000001 + + + + +
+ + EGD132 ASH RANGES + 511745N 0003956W -
511623N 0003942W -
511548N 0004034W -
511524N 0004300W -
511606N 0004309W -
511638N 0004259W -
511732N 0004116W -
511745N 0003956W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Remarks: SI 1983/162.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6655555556,51.2958333333,762 -0.6877777778,51.2922222222,762 -0.7163888889,51.27722222220001,762 -0.7191666667000001,51.2683333333,762 -0.7166666667,51.2566666667,762 -0.6761111111,51.2633333333,762 -0.6616666667,51.2730555556,762 -0.6655555556,51.2958333333,762 + + + + +
+ + EGD133A PIRBRIGHT + 511922N 0003907W -
511915N 0003858W -
511828N 0003951W -
511816N 0004028W -
511815N 0004103W -
511830N 0004118W -
511922N 0003907W
Upper limit: 1200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6519444444,51.32277777779999,365.76 -0.6883333333,51.3083333333,365.76 -0.6841666667,51.30416666670001,365.76 -0.6744444444,51.3044444444,365.76 -0.6641666667,51.3077777778,365.76 -0.6494444444,51.3208333333,365.76 -0.6519444444,51.32277777779999,365.76 + + + + +
+ + EGD133B PIRBRIGHT + 512040N 0004029W -
512034N 0003957W -
511922N 0003907W -
511830N 0004118W -
511915N 0004146W -
512019N 0004158W -
512040N 0004029W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1200 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2400 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Farnborough Radar on 133.440 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01483-798304.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6747222222,51.3444444444,731.52 -0.6994444444,51.3386111111,731.52 -0.6961111111,51.3208333333,731.52 -0.6883333333,51.3083333333,731.52 -0.6519444444,51.32277777779999,731.52 -0.6658333333000001,51.34277777780001,731.52 -0.6747222222,51.3444444444,731.52 + + + + +
+ + EGD136 SHOEBURYNESS + 513217N 0004804E -
513017N 0005104E -
513030N 0004700E -
513217N 0004804E
Upper limit: 13000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8011111111,51.5380555556,3962.4 0.7833333333,51.5083333333,3962.4 0.8511111111000002,51.50472222219999,3962.4 0.8011111111,51.5380555556,3962.4 + + + + +
+ + EGD138A SHOEBURYNESS + 514000N 0010400E -
514000N 0011613E -
513714N 0011203E -
513714N 0005536E -
514000N 0010400E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 6000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0666666667,51.6666666667,18288 0.9266666667,51.6205555556,18288 1.2008333333,51.6205555556,18288 1.2702777778,51.6666666667,18288 1.0666666667,51.6666666667,18288 + + + + +
+ + EGD138B SHOEBURYNESS + 514200N 0011124E -
514200N 0011912E -
514000N 0011613E -
514000N 0010400E -
514200N 0011124E
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.19,51.7,1524 1.0666666667,51.6666666667,1524 1.2702777778,51.6666666667,1524 1.32,51.7,1524 1.19,51.7,1524 + + + + +
+ + EGD138C SHOEBURYNESS + 513700N 0005455E -
513755N 0005740E -
513638N 0005850E -
513544N 0005620E -
513700N 0005455E
Upper limit: 6000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: May be activated at the same time as EGD138A and/or EGD138D as a separate activity.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9152777778000001,51.6166666667,1828.8 0.9388888889,51.5955555556,1828.8 0.9805555555999999,51.6105555556,1828.8 0.9611111111,51.63194444440001,1828.8 0.9152777778000001,51.6166666667,1828.8 + + + + +
+ + EGD138D SHOEBURYNESS + 513714N 0005536E -
513714N 0011203E -
513000N 0005300E -
513009N 0005115E -
513217N 0004804E -
513400N 0005000E -
513500N 0005018E -
513541N 0005016E - then along the north coast of Foulness Island to
513700N 0005455E -
513714N 0005536E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 13,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9266666667,51.6205555556,18288 0.9152777778000001,51.6166666667,18288 0.915875,51.61495,18288 0.913075,51.6141194444,18288 0.9085638888999999,51.61360000000001,18288 0.9064277777999999,51.61410277779999,18288 0.9046694444,51.6136972222,18288 0.9015722222,51.6126944444,18288 0.8996138888999999,51.61373333329999,18288 0.8951472221999999,51.6139333333,18288 0.8891527778,51.6150694444,18288 0.877525,51.6140055556,18288 0.8742555556,51.61255833330001,18288 0.87235,51.6098166667,18288 0.8720472222,51.6004694444,18288 0.87065,51.5966361111,18288 0.8677638889000001,51.5943666667,18288 0.8625527777999999,51.5918861111,18288 0.8590694444,51.5916111111,18288 0.8508555556,51.5919,18288 0.8451333333,51.5927583333,18288 0.8405138889,51.59278055560001,18288 0.8377777778000001,51.5947222222,18288 0.8383333333,51.58333333329999,18288 0.8333333333000001,51.5666666667,18288 0.8011111111,51.5380555556,18288 0.8541666667,51.50249999999999,18288 0.8833333333,51.5,18288 1.2008333333,51.6205555556,18288 0.9266666667,51.6205555556,18288 + + + + +
+ + EGD139 FINGRINGHOE + 515000N 0005458E -
514954N 0005852E -
514833N 0005848E -
514839N 0005452E -
515000N 0005458E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01206-736149.

Remarks: SI 1974/665.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9161111111,51.83333333329999,609.6 0.9144444443999998,51.8108333333,609.6 0.98,51.8091666667,609.6 0.9811111111000002,51.8316666667,609.6 0.9161111111,51.83333333329999,609.6 + + + + +
+ + EGD141 HYTHE RANGES + 510419N 0010426E -
510212N 0010531E -
510120N 0010148E -
510158N 0010111E -
510323N 0010214E -
510419N 0010426E
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Lydd Approach on 120.705 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01303-225879.

Remarks: SI 1966/814.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0738888889,51.0719444444,975.36 1.0372222222,51.0563888889,975.36 1.0197222222,51.03277777780001,975.36 1.03,51.02222222220001,975.36 1.0919444444,51.0366666667,975.36 1.0738888889,51.0719444444,975.36 + + + + +
+ + EGD147 PONTRILAS + A circle, 2 NM radius, centred at 515800N 0025300W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: Activity: Para Dropping / Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information 124.750 MHz.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8833333333,51.999955951,3048 -2.8888787335,51.9997793836,3048 -2.8943652213,51.9992515574,3048 -2.8997345145,51.9983780795,3048 -2.9049295838,51.9971682287,3048 -2.9098952622,51.99563485620001,3048 -2.9145788343,51.9937942479,3048 -2.9189305979,51.9916659511,3048 -2.9229043934,51.98927256490001,3048 -2.9264580946,51.9866395,3048 -2.9295540548,51.9837947065,3048 -2.9321595054,51.9807683771,3048 -2.9342469009,51.9775926246,3048 -2.9357942078,51.9743011406,3048 -2.9367851343,51.970928837,3048 -2.9372092981,51.967511475,3048 -2.9370623318,51.9640852856,3048 -2.9363459229,51.96068658519999,3048 -2.9350677915,51.9573513906,3048 -2.933241602,51.9541150377,3048 -2.9308868144,51.9510118081,3048 -2.928028473,51.948074566,3048 -2.924696937899999,51.9453344117,3048 -2.9209275601,51.94282035329999,3048 -2.9167603059,51.9405590008,3048 -2.9122393324,51.93857428559999,3048 -2.907412519999999,51.9368872085,3048 -2.9023309674,51.9355156188,3048 -2.8970484519,51.9344740267,3048 -2.8916208636,51.93377345010001,3048 -2.8861056174,51.9334212994,3048 -2.8805610492,51.9334212994,3048 -2.8750458031,51.93377345010001,3048 -2.8696182148,51.9344740267,3048 -2.8643356993,51.9355156188,3048 -2.8592541466,51.9368872085,3048 -2.8544273343,51.93857428559999,3048 -2.8499063607,51.9405590008,3048 -2.8457391065,51.94282035329999,3048 -2.8419697288,51.9453344117,3048 -2.8386381936,51.948074566,3048 -2.8357798523,51.9510118081,3048 -2.8334250647,51.9541150377,3048 -2.8315988752,51.9573513906,3048 -2.8303207437,51.96068658519999,3048 -2.8296043349,51.9640852856,3048 -2.8294573685,51.967511475,3048 -2.8298815324,51.970928837,3048 -2.8308724589,51.9743011406,3048 -2.832419765800001,51.9775926246,3048 -2.8345071613,51.9807683771,3048 -2.8371126119,51.9837947065,3048 -2.8402085721,51.9866395,3048 -2.8437622732,51.98927256490001,3048 -2.8477360688,51.9916659511,3048 -2.8520878324,51.9937942479,3048 -2.8567714045,51.99563485620001,3048 -2.8617370829,51.9971682287,3048 -2.8669321522,51.9983780795,3048 -2.872301445400001,51.9992515574,3048 -2.8777879332,51.9997793836,3048 -2.8833333333,51.999955951,3048 + + + + +
+ + EGD148 KEEVIL + 511744N 0021016W -
511937N 0020745W -
512055N 0020410W -
511946N 0020305W -
511705N 0020312W -
511602N 0020657W -
511701N 0020929W -
511744N 0021016W
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Boscombe Down ATC on 126.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Salisbury Operations, Tel: 01980-674710.

Danger Area Authority: JHC HQ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1710333333,51.29568888890001,975.36 -2.1580805556,51.2835916667,975.36 -2.11575,51.2672444444,975.36 -2.0533333333,51.2847222222,975.36 -2.0513416667,51.3294194444,975.36 -2.0694666667,51.34871666669999,975.36 -2.1292833333,51.3269444444,975.36 -2.1710333333,51.29568888890001,975.36 + + + + +
+ + EGD201A ABERPORTH + 523427N 0052148W -
520903N 0050057W -
521000N 0050822W -
521307N 0051616W -
522013N 0052151W -
523427N 0052148W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3634016667,52.5740336111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.2711694444,52.2185361111,30449.52 -5.13935,52.1667388889,30449.52 -5.0158333333,52.15083333330001,30449.52 -5.3634016667,52.5740336111,30449.52 + + + + +
+ + EGD201B ABERPORTH + 530300N 0053000W -
531500N 0053000W -
532315N 0051017W -
532255N 0050000W -
531200N 0050000W -
530715N 0045319W -
530300N 0045319W following the line of latitude to -
530300N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL 145. Only available above FL 145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.0108888889,53.05,30449.52 -4.8886111111,53.05,30449.52 -4.8886111111,53.12083333329999,30449.52 -5,53.2,30449.52 -5,53.3819444444,30449.52 -5.1713888889,53.3875,30449.52 -5.5,53.25,30449.52 -5.5,53.05,30449.52 + + + + +
+ + EGD201C ABERPORTH + 525019N 0045319W -
524500N 0044018W -
524500N 0045319W -
525019N 0045319W
Upper limit: UNL
Lower limit: FL145
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,30449.52 -4.8886111111,52.75,30449.52 -4.6716305556,52.75,30449.52 -4.8886111111,52.83873333329999,30449.52 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.8886111111,52.83873333329999,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.75,4419.6 -4.8886111111,52.75,30449.52 -4.8886111111,52.83873333329999,30449.52 -4.8886111111,52.83873333329999,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.8886111111,52.75,4419.6 -4.6716305556,52.75,4419.6 -4.6716305556,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,52.75,4419.6 + + + + + + relativeToGround + + + relativeToGround + + -4.6716305556,52.75,4419.6 -4.8886111111,52.83873333329999,4419.6 -4.8886111111,52.83873333329999,30449.52 -4.6716305556,52.75,30449.52 -4.6716305556,52.75,4419.6 + + + + + +
+ + EGD201D ABERPORTH + 531035N 0053000W -
530300N 0051612W following the line of latitude to -
530300N 0053000W -
531035N 0053000W
Upper limit: UNL
Lower limit: FL55
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,30449.52 -5.5,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.2698722222,53.05,30449.52 -5.5,53.1764722222,30449.52 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.1764722222,1676.4 -5.5,53.05,1676.4 -5.5,53.05,30449.52 -5.5,53.1764722222,30449.52 -5.5,53.1764722222,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.5,53.05,1676.4 -5.3849361111,53.05,1676.4 -5.3849361111,53.05,30449.52 -5.5,53.05,30449.52 -5.5,53.05,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.3849361111,53.05,1676.4 -5.2698722222,53.05,1676.4 -5.2698722222,53.05,30449.52 -5.3849361111,53.05,30449.52 -5.3849361111,53.05,1676.4 + + + + + + relativeToGround + + + relativeToGround + + -5.2698722222,53.05,1676.4 -5.5,53.1764722222,1676.4 -5.5,53.1764722222,30449.52 -5.2698722222,53.05,30449.52 -5.2698722222,53.05,1676.4 + + + + + +
+ + EGD201F ABERPORTH + 521236N 0052244W -
521000N 0050822W -
520903N 0050057W -
520840N 0043847W -
520612N 0044900W -
520816N 0051829W -
521236N 0052244W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3787709722,52.2100607222,30449.52 -5.3080555556,52.1377777778,30449.52 -4.8166666667,52.1033333333,30449.52 -4.646375,52.14435,30449.52 -5.0158333333,52.15083333330001,30449.52 -5.13935,52.1667388889,30449.52 -5.3787709722,52.2100607222,30449.52 + + + + +
+ + EGD201G ABERPORTH + 524417N 0053000W -
523427N 0052148W -
522013N 0052151W -
521307N 0051616W -
521000N 0050822W -
521236N 0052244W -
522000N 0053000W -
524417N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: Normally FL145. Only available above FL145 for QinetiQ managed activity.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,52.73805555559999,30449.52 -5.5,52.3333333333,30449.52 -5.3787709722,52.2100607222,30449.52 -5.13935,52.1667388889,30449.52 -5.2711694444,52.2185361111,30449.52 -5.3641455556,52.3368058333,30449.52 -5.3634016667,52.5740336111,30449.52 -5.5,52.73805555559999,30449.52 + + + + +
+ + EGD201H ABERPORTH + 523000N 0051806W following the line of latitude to -
523000N 0041200W -
521600N 0041200W -
521000N 0042942W -
520848N 0042904W -
520702N 0043810W -
520840N 0043847W -
520903N 0050057W -
523000N 0051806W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3016805556,52.5,30449.52 -5.0158333333,52.15083333330001,30449.52 -4.646375,52.14435,30449.52 -4.6360805556,52.1171138889,30449.52 -4.4845083333,52.1468,30449.52 -4.495,52.16666666670001,30449.52 -4.2,52.26666666669999,30449.52 -4.2,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.8885503472,52.5,30449.52 -5.0262604167,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.3016805556,52.5,30449.52 + + + + +
+ + EGD201J ABERPORTH + 530300N 0053000W following the line of latitude to -
530300N 0045319W -
524500N 0045319W following the line of latitude to -
524500N 0044018W -
523316N 0041200W -
523000N 0041200W following the line of latitude to -
523000N 0051806W -
524417N 0053000W -
530300N 0053000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: SI 1976/64.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,53.05,30449.52 -5.5,52.73805555559999,30449.52 -5.3016805556,52.5,30449.52 -5.1639704861,52.5,30449.52 -5.0262604167,52.5,30449.52 -4.8885503472,52.5,30449.52 -4.7508402778,52.5,30449.52 -4.6131302083,52.5,30449.52 -4.4754201389,52.5,30449.52 -4.3377100694,52.5,30449.52 -4.2,52.5,30449.52 -4.2,52.5544888889,30449.52 -4.6716666667,52.75,30449.52 -4.7801388889,52.75,30449.52 -4.8886111111,52.75,30449.52 -4.8886111111,53.05,30449.52 -5.0108888889,53.05,30449.52 -5.1331666667,53.05,30449.52 -5.2554444444,53.05,30449.52 -5.3777222222,53.05,30449.52 -5.5,53.05,30449.52 + + + + +
+ + EGD201K ABERPORTH + 522000N 0053000W -
520816N 0051829W -
521038N 0053000W -
522000N 0053000W
Upper limit: FL145
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Target Towing / Balloons / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5,52.3333333333,4419.6 -5.5,52.17722222219999,4419.6 -5.3080555556,52.1377777778,4419.6 -5.5,52.3333333333,4419.6 + + + + +
+ + EGD202A WEST WALES + 521250N 0042121W -
521600N 0041200W -
521545N 0040958W -
520135N 0041430W -
520019N 0042519W -
521250N 0042121W
Upper limit: FL100
Lower limit: FL60
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202A and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.4219444444,52.0052777778,3048 -4.2416666667,52.0263888889,3048 -4.1661111111,52.2625,3048 -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,1828.8 -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.2,52.26666666669999,1828.8 -4.3558333333,52.21388888889999,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,1828.8 -4.4219444444,52.0052777778,1828.8 -4.4219444444,52.0052777778,3048 -4.3558333333,52.21388888889999,3048 -4.3558333333,52.21388888889999,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.4219444444,52.0052777778,1828.8 -4.2416666667,52.0263888889,1828.8 -4.2416666667,52.0263888889,3048 -4.4219444444,52.0052777778,3048 -4.4219444444,52.0052777778,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.2416666667,52.0263888889,1828.8 -4.1661111111,52.2625,1828.8 -4.1661111111,52.2625,3048 -4.2416666667,52.0263888889,3048 -4.2416666667,52.0263888889,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1661111111,52.2625,1828.8 -4.2,52.26666666669999,1828.8 -4.2,52.26666666669999,3048 -4.1661111111,52.2625,3048 -4.1661111111,52.2625,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.2,52.26666666669999,1828.8 -4.3558333333,52.21388888889999,1828.8 -4.3558333333,52.21388888889999,3048 -4.2,52.26666666669999,3048 -4.2,52.26666666669999,1828.8 + + + + + +
+ + EGD202B WEST WALES + 521250N 0042121W -
521600N 0041200W -
521433N 0040004W -
520320N 0040343W -
520545N 0042336W -
521250N 0042121W
Upper limit: FL225
Lower limit: FL100
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202B and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,6858 -4.3933333333,52.09583333330001,6858 -4.0619444444,52.0555555556,6858 -4.0011111111,52.24249999999999,6858 -4.2,52.26666666669999,6858 -4.3558333333,52.21388888889999,6858 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.3933333333,52.09583333330001,3048 -4.0619444444,52.0555555556,3048 -4.0011111111,52.24249999999999,3048 -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3558333333,52.21388888889999,3048 -4.3933333333,52.09583333330001,3048 -4.3933333333,52.09583333330001,6858 -4.3558333333,52.21388888889999,6858 -4.3558333333,52.21388888889999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.3933333333,52.09583333330001,3048 -4.0619444444,52.0555555556,3048 -4.0619444444,52.0555555556,6858 -4.3933333333,52.09583333330001,6858 -4.3933333333,52.09583333330001,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0619444444,52.0555555556,3048 -4.0011111111,52.24249999999999,3048 -4.0011111111,52.24249999999999,6858 -4.0619444444,52.0555555556,6858 -4.0619444444,52.0555555556,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.2,52.26666666669999,3048 -4.2,52.26666666669999,6858 -4.0011111111,52.24249999999999,6858 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.2,52.26666666669999,3048 -4.3558333333,52.21388888889999,3048 -4.3558333333,52.21388888889999,6858 -4.2,52.26666666669999,6858 -4.2,52.26666666669999,3048 + + + + + +
+ + EGD202C WEST WALES + 521433N 0040004W -
521047N 0033002W -
520721N 0033015W -
520501N 0033532W -
520211N 0034019W -
520030N 0034053W -
520320N 0040343W -
521433N 0040004W
Upper limit: FL225
Lower limit: FL100
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202C and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,6858 -4.0619444444,52.0555555556,6858 -3.6813888889,52.0083333333,6858 -3.6719444444,52.03638888890001,6858 -3.5922222222,52.08361111109999,6858 -3.504166666700001,52.1225,6858 -3.5005555556,52.17972222220001,6858 -4.0011111111,52.24249999999999,6858 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.0619444444,52.0555555556,3048 -3.6813888889,52.0083333333,3048 -3.6719444444,52.03638888890001,3048 -3.5922222222,52.08361111109999,3048 -3.504166666700001,52.1225,3048 -3.5005555556,52.17972222220001,3048 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0011111111,52.24249999999999,3048 -4.0619444444,52.0555555556,3048 -4.0619444444,52.0555555556,6858 -4.0011111111,52.24249999999999,6858 -4.0011111111,52.24249999999999,3048 + + + + + + relativeToGround + + + relativeToGround + + -4.0619444444,52.0555555556,3048 -3.6813888889,52.0083333333,3048 -3.6813888889,52.0083333333,6858 -4.0619444444,52.0555555556,6858 -4.0619444444,52.0555555556,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.6813888889,52.0083333333,3048 -3.6719444444,52.03638888890001,3048 -3.6719444444,52.03638888890001,6858 -3.6813888889,52.0083333333,6858 -3.6813888889,52.0083333333,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.6719444444,52.03638888890001,3048 -3.5922222222,52.08361111109999,3048 -3.5922222222,52.08361111109999,6858 -3.6719444444,52.03638888890001,6858 -3.6719444444,52.03638888890001,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.5922222222,52.08361111109999,3048 -3.504166666700001,52.1225,3048 -3.504166666700001,52.1225,6858 -3.5922222222,52.08361111109999,6858 -3.5922222222,52.08361111109999,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.504166666700001,52.1225,3048 -3.5005555556,52.17972222220001,3048 -3.5005555556,52.17972222220001,6858 -3.504166666700001,52.1225,6858 -3.504166666700001,52.1225,3048 + + + + + + relativeToGround + + + relativeToGround + + -3.5005555556,52.17972222220001,3048 -4.0011111111,52.24249999999999,3048 -4.0011111111,52.24249999999999,6858 -3.5005555556,52.17972222220001,6858 -3.5005555556,52.17972222220001,3048 + + + + + +
+ + EGD202D WEST WALES + 520840N 0043847W -
520702N 0043810W -
520848N 0042904W -
521000N 0042942W -
521250N 0042121W -
520019N 0042519W -
515840N 0043902W -
520555N 0044130W thence clockwise by the arc of a circle radius 5 NM centred on 520653N 0043334W to
520801N 0044128W -
520840N 0043847W
Upper limit: FL125
Lower limit: SFC
Class: AMC - Manageable.

Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Aberporth Radar on 120.835 MHz / 244.575 MHz, or West Wales Radar on 127.090 MHz. SUAAIS: West Wales Information on 122.155 MHz.

Contact: Pre-flight information: Range Control, Tel: 01239-813219.

Remarks: Pilots will be required to comply with ATC instructions whilst crossing EGD202D and will be provided with an appropriate Flight Information Service. Pilots who may be unable to comply with ATC instructions should not request a crossing clearance.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.646375,52.14435,3810 -4.6911111111,52.1336111111,3810 -4.6923695661,52.1286290972,3810 -4.6934867815,52.1236458923,3810 -4.6941112708,52.118630173,3810 -4.6942409049,52.1136003736,3810 -4.6938753744,52.10857497359999,3810 -4.6930161885,52.1035724304,3810 -4.6916666667,52.0986111111,3810 -4.6505555556,51.9777777778,3810 -4.4219444444,52.0052777778,3810 -4.3558333333,52.21388888889999,3810 -4.495,52.16666666670001,3810 -4.4845083333,52.1468,3810 -4.6360805556,52.1171138889,3810 -4.646375,52.14435,3810 + + + + +
+ + EGD203 SENNYBRIDGE + 520743N 0032924W -
520613N 0032645W -
520451N 0032532W -
520252N 0032804W -
520156N 0032943W -
520150N 0033139W -
515858N 0033729W -
515815N 0033935W -
515947N 0034105W -
520211N 0034019W -
520501N 0033532W -
520743N 0032924W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits:
Upper Limit: ALT 23000 Mon-Fri 0800-1800 (0700-1700).
Upper Limit: ALT 18000 Mon-Fri 1800-0800 (1700-0700), Fri 1800 (1700) - Mon 0800 (0700).

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01874-635599.

Remarks: SI 1974/1773.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.49,52.1286111111,7010.400000000001 -3.5922222222,52.08361111109999,7010.400000000001 -3.6719444444,52.03638888890001,7010.400000000001 -3.6847222222,51.9963888889,7010.400000000001 -3.659722222200001,51.97083333330001,7010.400000000001 -3.6247222222,51.9827777778,7010.400000000001 -3.5275,52.0305555556,7010.400000000001 -3.4952777778,52.0322222222,7010.400000000001 -3.4677777778,52.0477777778,7010.400000000001 -3.4255555556,52.08083333329999,7010.400000000001 -3.4458333333,52.1036111111,7010.400000000001 -3.49,52.1286111111,7010.400000000001 + + + + +
+ + EGD206 CARDINGTON + A circle, 1 NM radius, centred at 520621N 0002521W
Upper limit: 6000 FT MSL
Lower limit: SFC
Class: Activity: Balloons / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information: Cardington Met Office, Tel: 01234-744658, Mob: 07513-786573.

Danger Area Authority: MET Office.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4225,52.12247760369999,1828.8 -0.4264370798,52.1223001664,1828.8 -0.4302901553999999,52.1217716404,1828.8 -0.433977021,52.1209033022,1828.8 -0.437419028,52.1197136782,1828.8 -0.4405427677,52.1182281473,1828.8 -0.4432816393,52.1164783985,1828.8 -0.4455772722,52.1145017531,1828.8 -0.4473807689000001,52.11234036690001,1828.8 -0.4486537454,52.11004032899999,1828.8 -0.449369144,52.10765067820001,1828.8 -0.4495118043,52.1052223559,1828.8 -0.4490787784,52.1028071196,1828.8 -0.4480793863,52.10045643960001,1828.8 -0.4465350094000001,52.0982204027,1828.8 -0.4444786278,52.09614664570001,1828.8 -0.4419541121,52.0942793417,1828.8 -0.4390152849000001,52.09265826130001,1828.8 -0.4357247719,52.0913179268,1828.8 -0.4321526683,52.0902868787,1828.8 -0.4283750477,52.0895870705,1828.8 -0.4244723461,52.0892334015,1828.8 -0.4205276539,52.0892334015,1828.8 -0.4166249523000001,52.0895870705,1828.8 -0.4128473317,52.0902868787,1828.8 -0.4092752281,52.0913179268,1828.8 -0.4059847151,52.09265826130001,1828.8 -0.4030458879,52.0942793417,1828.8 -0.4005213722,52.09614664570001,1828.8 -0.3984649906,52.0982204027,1828.8 -0.3969206137,52.10045643960001,1828.8 -0.3959212216,52.1028071196,1828.8 -0.3954881957,52.1052223559,1828.8 -0.395630856,52.10765067820001,1828.8 -0.3963462546,52.11004032899999,1828.8 -0.3976192311,52.11234036690001,1828.8 -0.3994227277999999,52.1145017531,1828.8 -0.4017183606999999,52.1164783985,1828.8 -0.4044572323,52.1182281473,1828.8 -0.407580972,52.1197136782,1828.8 -0.411022979,52.1209033022,1828.8 -0.4147098446,52.1217716404,1828.8 -0.4185629202,52.1223001664,1828.8 -0.4225,52.12247760369999,1828.8 + + + + +
+ + EGD207 HOLBEACH + 524830N 0001200E -
525400N 0000633E thence clockwise by the arc of a circle radius 6.5 NM centred on 525000N 0001500E to
525300N 0002430E -
524830N 0002000E -
524830N 0001200E
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Holbeach Range on 122.750 MHz when open. SUAAIS: Holbeach Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Ops, Tel: 01406-550083. Booking: Range ATC, Tel: 01406-550364 Ext 7119.

Remarks: Airborne bookings and free-calling aircraft accepted subject to availability. Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Donna Nook and Pembrey AWRs. Ensure crossing clearance request is specific to Holbeach AWR. SI 1939/1608. UAS BVLOS will not be conducted above 18000 FT ALT (12000 FT ALT in the event of the activation of Contingency Airway T999).

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2,52.8083333333,7010.400000000001 0.3333333333,52.8083333333,7010.400000000001 0.4083333333,52.88333333329999,7010.400000000001 0.4035323371,52.888770376,7010.400000000001 0.3980704212,52.8939769833,7010.400000000001 0.3921256339,52.89898667170001,7010.400000000001 0.3857172013,52.9037831019,7010.400000000001 0.3788658825999999,52.9083506248,7010.400000000001 0.3715939029,52.91267433339999,7010.400000000001 0.3639248819000001,52.916740112,7010.400000000001 0.3558837567000001,52.9205346833,7010.400000000001 0.3474967008,52.9240456522,7010.400000000001 0.338791038,52.9272615471,7010.400000000001 0.3297951528,52.9301718581,7010.400000000001 0.3205383966,52.93276707209999,7010.400000000001 0.3110509909,52.9350387042,7010.400000000001 0.3013639265,52.9369793263,7010.400000000001 0.2915088612,52.9385825917,7010.400000000001 0.2815180137,52.9398432563,7010.400000000001 0.2714240568,52.9407571964,7010.400000000001 0.2612600077,52.941321422,7010.400000000001 0.2510591185,52.9415340873,7010.400000000001 0.2408547639,52.9413944965,7010.400000000001 0.2306803307,52.9409031063,7010.400000000001 0.2205691054,52.94006152430001,7010.400000000001 0.2105541631,52.93887250379999,7010.400000000001 0.2006682571,52.93733993410001,7010.400000000001 0.1909437092,52.9354688284,7010.400000000001 0.1814123023,52.933265306,7010.400000000001 0.1721051742,52.9307365725,7010.400000000001 0.1630527144,52.92789089589999,7010.400000000001 0.1542844628,52.9247375784,7010.400000000001 0.1458290125,52.92128692579999,7010.400000000001 0.1377139148,52.9175502132,7010.400000000001 0.1299655892,52.9135396473,7010.400000000001 0.1226092361,52.9092683259,7010.400000000001 0.1156687551,52.90475019460001,7010.400000000001 0.1091666667,52.9,7010.400000000001 0.2,52.8083333333,7010.400000000001 + + + + +
+ + EGD208 STANFORD + 523315N 0004050E -
523320N 0004500E -
523255N 0004800E -
523045N 0005000E -
522650N 0005050E -
522620N 0004830E -
522800N 0004500E -
522900N 0003900E -
523100N 0004000E -
523315N 0004050E
Upper limit: 7500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 7500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Lakenheath Zone on 128.900 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01842-855367.

Remarks: SI 1970/909 & SI 1975/24 (Amendment).

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6805555556,52.5541666667,2286 0.6666666667,52.51666666669999,2286 0.65,52.4833333333,2286 0.75,52.46666666670001,2286 0.8083333332999999,52.4388888889,2286 0.8472222221999999,52.4472222222,2286 0.8333333333000001,52.5125,2286 0.8,52.5486111111,2286 0.75,52.55555555559999,2286 0.6805555556,52.5541666667,2286 + + + + +
+ + EGD211 SWYNNERTON + A circle, 0.5 NM radius, centred at 525352N 0021312W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.750 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.22,52.9060987986,731.52 -2.2227704214,52.9059284347,731.52 -2.2254273585,52.9054243214,731.52 -2.2278619831,52.9046071082,731.52 -2.2299745875,52.9035102684,731.52 -2.2316786715,52.9021787258,731.52 -2.2329044861,52.9006670125,731.52 -2.2336018855,52.8990370336,731.52 -2.2337423743,52.89735552980001,731.52 -2.233320265,52.8956913442,731.52 -2.2323529,52.8941126028,731.52 -2.230879932,52.89268392709999,731.52 -2.2289616929,52.8914637897,731.52 -2.2266767188,52.8905021241,731.52 -2.2241185345,52.8898382828,731.52 -2.221391828,52.8894994296,731.52 -2.218608172,52.8894994296,731.52 -2.2158814655,52.8898382828,731.52 -2.2133232812,52.8905021241,731.52 -2.2110383071,52.8914637897,731.52 -2.209120068,52.89268392709999,731.52 -2.2076471,52.8941126028,731.52 -2.206679735,52.8956913442,731.52 -2.2062576257,52.89735552980001,731.52 -2.2063981145,52.8990370336,731.52 -2.2070955139,52.9006670125,731.52 -2.2083213285,52.9021787258,731.52 -2.2100254125,52.9035102684,731.52 -2.2121380169,52.9046071082,731.52 -2.2145726415,52.9054243214,731.52 -2.2172295786,52.9059284347,731.52 -2.22,52.9060987986,731.52 + + + + +
+ + EGD213 KINETON + A circle, 700 M radius, centred at 520902N 0012656W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Coventry Information on 123.830 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01869-257489.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4488888889,52.1568465441,731.52 -1.4512476826,52.1566769462,731.52 -1.4534792617,52.1561772992,731.52 -1.4554632808,52.1553745497,731.52 -1.45709276,52.1543119889,731.52 -1.4582798567,52.15304691579999,731.52 -1.4589606006,52.1516475448,731.52 -1.4590983369,52.15018932510001,731.52 -1.4586856924,52.1487508716,731.52 -1.4577449627,52.1474097263,731.52 -1.4563268989,52.14623817889999,731.52 -1.4545079643,52.14529937230001,731.52 -1.4523862089,52.1446439021,731.52 -1.4500759857,52.1443070918,731.52 -1.4477017921,52.1443070918,731.52 -1.4453915689,52.1446439021,731.52 -1.4432698135,52.14529937230001,731.52 -1.4414508789,52.14623817889999,731.52 -1.4400328151,52.1474097263,731.52 -1.4390920853,52.1487508716,731.52 -1.4386794409,52.15018932510001,731.52 -1.4388171771,52.1516475448,731.52 -1.4394979211,52.15304691579999,731.52 -1.4406850178,52.1543119889,731.52 -1.4423144969,52.1553745497,731.52 -1.4442985161,52.1561772992,731.52 -1.4465300952,52.1566769462,731.52 -1.4488888889,52.1568465441,731.52 + + + + +
+ + EGD215 NORTH LUFFENHAM + A circle, 610 M radius, centred at 523754N 0003557W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information: Guard Room, Tel: 01780-727644.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5991666667,52.63714836539999,731.52 -0.6014074807000001,52.6369761266,731.52 -0.6035074459999999,52.63647023659999,731.52 -0.6053345765,52.635662493,731.52 -0.6067740508,52.6346036641,731.52 -0.6077354312,52.6333602954,731.52 -0.6081583435,52.6320105244,731.52 -0.6080162628,52.6306391677,731.52 -0.6073181676,52.6293323909,731.52 -0.6061079637,52.6281722944,731.52 -0.6044617146,52.62723175719999,731.52 -0.6024828569,52.62656986109999,731.52 -0.600295702,52.62622818239999,731.52 -0.5980376314,52.62622818239999,731.52 -0.5958504764,52.62656986109999,731.52 -0.5938716187999999,52.62723175719999,731.52 -0.5922253696999999,52.6281722944,731.52 -0.5910151658,52.6293323909,731.52 -0.5903170706,52.6306391677,731.52 -0.5901749898,52.6320105244,731.52 -0.5905979021,52.6333602954,731.52 -0.5915592825,52.6346036641,731.52 -0.5929987568,52.635662493,731.52 -0.5948258873,52.63647023659999,731.52 -0.5969258527,52.6369761266,731.52 -0.5991666667,52.63714836539999,731.52 + + + + +
+ + EGD216 CREDENHILL + A circle, 2 NM radius, centred at 520453N 0024806W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2300 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 10,000 FT ALT by NOTAM.

Activity: Para Dropping / Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 124.750 MHz.

Danger Area Authority: HQ Land.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8016666667,52.1146775213,3048 -2.8072262898,52.1145009569,3048 -2.8127268489,52.1139731394,3048 -2.8181099118,52.113099676,3048 -2.8233183024,52.1118898454,3048 -2.828296712,52.1103564987,3048 -2.832992289499999,52.10851592179999,3048 -2.8373552052,52.1063876615,3048 -2.8413391811,52.10399431700001,3048 -2.8449019829,52.10136129840001,3048 -2.8480058678,52.0985165558,3048 -2.850617983499999,52.09549028130001,3048 -2.8527107142,52.0923145874,3048 -2.8542619706,52.089023165,3048 -2.8552554197,52.08565092560001,3048 -2.8556806534,52.0822336298,3048 -2.8555332935,52.0788075078,3048 -2.854815033,52.07540887529999,3048 -2.8535336121,52.07207374830001,3048 -2.851702731,52.0688374621,3048 -2.8493419001,52.0657342973,3048 -2.8464762284,52.0627971173,3048 -2.8431361539,52.0600570218,3048 -2.8393571186,52.0575430179,3048 -2.835179191,52.05528171489999,3048 -2.8306466414,52.0532970434,3048 -2.8258074726,52.0516100039,3048 -2.8207129137,52.05023844490001,3048 -2.8154168795,52.0491968762,3048 -2.8099754026,52.0484963154,3048 -2.8044460442,52.0481441727,3048 -2.7988872891,52.0481441727,3048 -2.7933579308,52.0484963154,3048 -2.7879164539,52.0491968762,3048 -2.7826204196,52.05023844490001,3048 -2.7775258607,52.0516100039,3048 -2.772686692,52.0532970434,3048 -2.7681541423,52.05528171489999,3048 -2.7639762147,52.0575430179,3048 -2.7601971794,52.0600570218,3048 -2.7568571049,52.0627971173,3048 -2.7539914332,52.0657342973,3048 -2.7516306023,52.0688374621,3048 -2.7497997213,52.07207374830001,3048 -2.7485183003,52.07540887529999,3048 -2.7478000398,52.0788075078,3048 -2.74765268,52.0822336298,3048 -2.7480779137,52.08565092560001,3048 -2.7490713628,52.089023165,3048 -2.7506226191,52.0923145874,3048 -2.7527153499,52.09549028130001,3048 -2.7553274655,52.0985165558,3048 -2.7584313504,52.10136129840001,3048 -2.7619941522,52.10399431700001,3048 -2.7659781281,52.1063876615,3048 -2.7703410438,52.10851592179999,3048 -2.7750366213,52.1103564987,3048 -2.7800150309,52.1118898454,3048 -2.7852234215,52.113099676,3048 -2.7906064844,52.1139731394,3048 -2.7961070436,52.1145009569,3048 -2.8016666667,52.1146775213,3048 + + + + +
+ + EGD217A LLANBEDR + 525022N 0040522W -
524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -
525022N 0040522W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + +
+ + EGD217B LLANBEDR + 525306N 0040947W -
525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -
525306N 0040947W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + +
+ + EGD217C LLANBEDR + 524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524603N 0040510W -
523933N 0041231W -
524222N 0041917W -
524942N 0041102W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 + + + + +
+ + EGD217D LLANBEDR + 524222N 0041917W -
523933N 0041231W -
523526N 0041712W -
523816N 0042359W -
524222N 0041917W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,1828.8 -4.3995916667,52.63763888889999,1828.8 -4.2867416667,52.5906805556,1828.8 -4.2084722222,52.6592083333,1828.8 -4.3215111111,52.70620277780001,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.3995916667,52.63763888889999,609.6 -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.3995916667,52.63763888889999,609.6 -4.3995916667,52.63763888889999,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3995916667,52.63763888889999,609.6 -4.2867416667,52.5906805556,609.6 -4.2867416667,52.5906805556,1828.8 -4.3995916667,52.63763888889999,1828.8 -4.3995916667,52.63763888889999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2867416667,52.5906805556,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8 -4.2867416667,52.5906805556,1828.8 -4.2867416667,52.5906805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2084722222,52.6592083333,609.6 -4.3215111111,52.70620277780001,609.6 -4.3215111111,52.70620277780001,1828.8 -4.2084722222,52.6592083333,1828.8 -4.2084722222,52.6592083333,609.6 + + + + + +
+ + EGD217E LLANBEDR + 525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
524333N 0040503W -
525307N 0040530W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + +
+ + EGD217F LLANBEDR + 525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
525307N 0040530W -
525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
525028N 0040939W -
525306N 0040947W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + +
+ + EGD217G LLANBEDR + 525022N 0040522W -
524617N 0040510W thence clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to -
525022N 0040522W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,1828.8 -4.0949801674,52.84151682579999,1828.8 -4.1007438086,52.8431637779,1828.8 -4.1067350168,52.8444800679,1828.8 -4.1129021488,52.8454543458,1828.8 -4.1191920321,52.84607821,1828.8 -4.1255504268,52.84634628049999,1828.8 -4.131922497,52.8462562454,1828.8 -4.1382532879,52.8458088811,1828.8 -4.1444882038,52.8450080457,1828.8 -4.1505734827,52.8438606453,1828.8 -4.1564566639,52.8423765741,1828.8 -4.1620870429,52.8405686282,1828.8 -4.1674161122,52.8384523943,1828.8 -4.1723979807,52.83604611490001,1828.8 -4.1769897708,52.8333705291,1828.8 -4.1811519882,52.8304486936,1828.8 -4.184848862,52.8273057818,1828.8 -4.188048651,52.8239688666,1828.8 -4.1907239156,52.82046668539999,1828.8 -4.1928517505,52.8168293921,1828.8 -4.1944139782,52.813088296,1828.8 -4.1953973017,52.8092755921,1828.8 -4.1957934135,52.8054240831,1828.8 -4.1955990621,52.8015668967,1828.8 -4.1948160749,52.7977372011,1828.8 -4.1934513366,52.79396791920001,1828.8 -4.1915167256,52.7902914462,1828.8 -4.189029006,52.7867393717,1828.8 -4.1860096801,52.783342209,1828.8 -4.1824847989,52.7801291336,1828.8 -4.1784847357,52.77712773390001,1828.8 -4.1740439228,52.77436377539999,1828.8 -4.169200554,52.77186098050001,1828.8 -4.1639962563,52.7696408264,1828.8 -4.1584757326,52.7677223618,1828.8 -4.1526863794,52.7661220445,1828.8 -4.1466778812,52.7648536015,1828.8 -4.1405017878,52.76392791199999,1828.8 -4.134211074,52.7633529149,1828.8 -4.1278596898,52.7631335411,1828.8 -4.1215021006,52.7632716721,1828.8 -4.115192825,52.7637661231,1828.8 -4.1089859706,52.764612654,1828.8 -4.1029347739,52.76580400480001,1828.8 -4.0970911477,52.76732995779999,1828.8 -4.0915052387,52.7691774242,1828.8 -4.086225,52.7713305556,1828.8 -4.0894944444,52.8395527778,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0949801674,52.84151682579999,609.6 -4.0949801674,52.84151682579999,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0949801674,52.84151682579999,609.6 -4.1007438086,52.8431637779,609.6 -4.1007438086,52.8431637779,1828.8 -4.0949801674,52.84151682579999,1828.8 -4.0949801674,52.84151682579999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1007438086,52.8431637779,609.6 -4.1067350168,52.8444800679,609.6 -4.1067350168,52.8444800679,1828.8 -4.1007438086,52.8431637779,1828.8 -4.1007438086,52.8431637779,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1067350168,52.8444800679,609.6 -4.1129021488,52.8454543458,609.6 -4.1129021488,52.8454543458,1828.8 -4.1067350168,52.8444800679,1828.8 -4.1067350168,52.8444800679,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1129021488,52.8454543458,609.6 -4.1191920321,52.84607821,609.6 -4.1191920321,52.84607821,1828.8 -4.1129021488,52.8454543458,1828.8 -4.1129021488,52.8454543458,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1191920321,52.84607821,609.6 -4.1255504268,52.84634628049999,609.6 -4.1255504268,52.84634628049999,1828.8 -4.1191920321,52.84607821,1828.8 -4.1191920321,52.84607821,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1255504268,52.84634628049999,609.6 -4.131922497,52.8462562454,609.6 -4.131922497,52.8462562454,1828.8 -4.1255504268,52.84634628049999,1828.8 -4.1255504268,52.84634628049999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.131922497,52.8462562454,609.6 -4.1382532879,52.8458088811,609.6 -4.1382532879,52.8458088811,1828.8 -4.131922497,52.8462562454,1828.8 -4.131922497,52.8462562454,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1382532879,52.8458088811,609.6 -4.1444882038,52.8450080457,609.6 -4.1444882038,52.8450080457,1828.8 -4.1382532879,52.8458088811,1828.8 -4.1382532879,52.8458088811,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1444882038,52.8450080457,609.6 -4.1505734827,52.8438606453,609.6 -4.1505734827,52.8438606453,1828.8 -4.1444882038,52.8450080457,1828.8 -4.1444882038,52.8450080457,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1505734827,52.8438606453,609.6 -4.1564566639,52.8423765741,609.6 -4.1564566639,52.8423765741,1828.8 -4.1505734827,52.8438606453,1828.8 -4.1505734827,52.8438606453,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1564566639,52.8423765741,609.6 -4.1620870429,52.8405686282,609.6 -4.1620870429,52.8405686282,1828.8 -4.1564566639,52.8423765741,1828.8 -4.1564566639,52.8423765741,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1620870429,52.8405686282,609.6 -4.1674161122,52.8384523943,609.6 -4.1674161122,52.8384523943,1828.8 -4.1620870429,52.8405686282,1828.8 -4.1620870429,52.8405686282,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1674161122,52.8384523943,609.6 -4.1723979807,52.83604611490001,609.6 -4.1723979807,52.83604611490001,1828.8 -4.1674161122,52.8384523943,1828.8 -4.1674161122,52.8384523943,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1723979807,52.83604611490001,609.6 -4.1769897708,52.8333705291,609.6 -4.1769897708,52.8333705291,1828.8 -4.1723979807,52.83604611490001,1828.8 -4.1723979807,52.83604611490001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769897708,52.8333705291,609.6 -4.1811519882,52.8304486936,609.6 -4.1811519882,52.8304486936,1828.8 -4.1769897708,52.8333705291,1828.8 -4.1769897708,52.8333705291,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1811519882,52.8304486936,609.6 -4.184848862,52.8273057818,609.6 -4.184848862,52.8273057818,1828.8 -4.1811519882,52.8304486936,1828.8 -4.1811519882,52.8304486936,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.184848862,52.8273057818,609.6 -4.188048651,52.8239688666,609.6 -4.188048651,52.8239688666,1828.8 -4.184848862,52.8273057818,1828.8 -4.184848862,52.8273057818,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.188048651,52.8239688666,609.6 -4.1907239156,52.82046668539999,609.6 -4.1907239156,52.82046668539999,1828.8 -4.188048651,52.8239688666,1828.8 -4.188048651,52.8239688666,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1907239156,52.82046668539999,609.6 -4.1928517505,52.8168293921,609.6 -4.1928517505,52.8168293921,1828.8 -4.1907239156,52.82046668539999,1828.8 -4.1907239156,52.82046668539999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1928517505,52.8168293921,609.6 -4.1944139782,52.813088296,609.6 -4.1944139782,52.813088296,1828.8 -4.1928517505,52.8168293921,1828.8 -4.1928517505,52.8168293921,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1944139782,52.813088296,609.6 -4.1953973017,52.8092755921,609.6 -4.1953973017,52.8092755921,1828.8 -4.1944139782,52.813088296,1828.8 -4.1944139782,52.813088296,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1953973017,52.8092755921,609.6 -4.1957934135,52.8054240831,609.6 -4.1957934135,52.8054240831,1828.8 -4.1953973017,52.8092755921,1828.8 -4.1953973017,52.8092755921,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957934135,52.8054240831,609.6 -4.1955990621,52.8015668967,609.6 -4.1955990621,52.8015668967,1828.8 -4.1957934135,52.8054240831,1828.8 -4.1957934135,52.8054240831,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1955990621,52.8015668967,609.6 -4.1948160749,52.7977372011,609.6 -4.1948160749,52.7977372011,1828.8 -4.1955990621,52.8015668967,1828.8 -4.1955990621,52.8015668967,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1948160749,52.7977372011,609.6 -4.1934513366,52.79396791920001,609.6 -4.1934513366,52.79396791920001,1828.8 -4.1948160749,52.7977372011,1828.8 -4.1948160749,52.7977372011,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1934513366,52.79396791920001,609.6 -4.1915167256,52.7902914462,609.6 -4.1915167256,52.7902914462,1828.8 -4.1934513366,52.79396791920001,1828.8 -4.1934513366,52.79396791920001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1915167256,52.7902914462,609.6 -4.189029006,52.7867393717,609.6 -4.189029006,52.7867393717,1828.8 -4.1915167256,52.7902914462,1828.8 -4.1915167256,52.7902914462,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.189029006,52.7867393717,609.6 -4.1860096801,52.783342209,609.6 -4.1860096801,52.783342209,1828.8 -4.189029006,52.7867393717,1828.8 -4.189029006,52.7867393717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1860096801,52.783342209,609.6 -4.1824847989,52.7801291336,609.6 -4.1824847989,52.7801291336,1828.8 -4.1860096801,52.783342209,1828.8 -4.1860096801,52.783342209,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1824847989,52.7801291336,609.6 -4.1784847357,52.77712773390001,609.6 -4.1784847357,52.77712773390001,1828.8 -4.1824847989,52.7801291336,1828.8 -4.1824847989,52.7801291336,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1784847357,52.77712773390001,609.6 -4.1740439228,52.77436377539999,609.6 -4.1740439228,52.77436377539999,1828.8 -4.1784847357,52.77712773390001,1828.8 -4.1784847357,52.77712773390001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1740439228,52.77436377539999,609.6 -4.169200554,52.77186098050001,609.6 -4.169200554,52.77186098050001,1828.8 -4.1740439228,52.77436377539999,1828.8 -4.1740439228,52.77436377539999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.169200554,52.77186098050001,609.6 -4.1639962563,52.7696408264,609.6 -4.1639962563,52.7696408264,1828.8 -4.169200554,52.77186098050001,1828.8 -4.169200554,52.77186098050001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1639962563,52.7696408264,609.6 -4.1584757326,52.7677223618,609.6 -4.1584757326,52.7677223618,1828.8 -4.1639962563,52.7696408264,1828.8 -4.1639962563,52.7696408264,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1584757326,52.7677223618,609.6 -4.1526863794,52.7661220445,609.6 -4.1526863794,52.7661220445,1828.8 -4.1584757326,52.7677223618,1828.8 -4.1584757326,52.7677223618,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1526863794,52.7661220445,609.6 -4.1466778812,52.7648536015,609.6 -4.1466778812,52.7648536015,1828.8 -4.1526863794,52.7661220445,1828.8 -4.1526863794,52.7661220445,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1466778812,52.7648536015,609.6 -4.1405017878,52.76392791199999,609.6 -4.1405017878,52.76392791199999,1828.8 -4.1466778812,52.7648536015,1828.8 -4.1466778812,52.7648536015,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1405017878,52.76392791199999,609.6 -4.134211074,52.7633529149,609.6 -4.134211074,52.7633529149,1828.8 -4.1405017878,52.76392791199999,1828.8 -4.1405017878,52.76392791199999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.134211074,52.7633529149,609.6 -4.1278596898,52.7631335411,609.6 -4.1278596898,52.7631335411,1828.8 -4.134211074,52.7633529149,1828.8 -4.134211074,52.7633529149,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1278596898,52.7631335411,609.6 -4.1215021006,52.7632716721,609.6 -4.1215021006,52.7632716721,1828.8 -4.1278596898,52.7631335411,1828.8 -4.1278596898,52.7631335411,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1215021006,52.7632716721,609.6 -4.115192825,52.7637661231,609.6 -4.115192825,52.7637661231,1828.8 -4.1215021006,52.7632716721,1828.8 -4.1215021006,52.7632716721,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.115192825,52.7637661231,609.6 -4.1089859706,52.764612654,609.6 -4.1089859706,52.764612654,1828.8 -4.115192825,52.7637661231,1828.8 -4.115192825,52.7637661231,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1089859706,52.764612654,609.6 -4.1029347739,52.76580400480001,609.6 -4.1029347739,52.76580400480001,1828.8 -4.1089859706,52.764612654,1828.8 -4.1089859706,52.764612654,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1029347739,52.76580400480001,609.6 -4.0970911477,52.76732995779999,609.6 -4.0970911477,52.76732995779999,1828.8 -4.1029347739,52.76580400480001,1828.8 -4.1029347739,52.76580400480001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0970911477,52.76732995779999,609.6 -4.0915052387,52.7691774242,609.6 -4.0915052387,52.7691774242,1828.8 -4.0970911477,52.76732995779999,1828.8 -4.0970911477,52.76732995779999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0915052387,52.7691774242,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.0915052387,52.7691774242,1828.8 -4.0915052387,52.7691774242,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + +
+ + EGD217H LLANBEDR + 525306N 0040947W -
525028N 0040939W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524333N 0040503W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to -
525306N 0040947W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,1828.8 -4.1716703219,52.88348920120001,1828.8 -4.1800610524,52.8815618217,1828.8 -4.1882253836,52.879307044,1828.8 -4.1961284314,52.8767345124,1828.8 -4.203736446,52.8738552286,1828.8 -4.2110169583,52.87068150359999,1828.8 -4.2179389192,52.8672269048,1828.8 -4.2244728329,52.8635061966,1828.8 -4.2305908832,52.8595352771,1828.8 -4.2362670523,52.8553311089,1828.8 -4.2414772309,52.8509116461,1828.8 -4.24619932,52.8462957566,1828.8 -4.2504133239,52.8415031405,1828.8 -4.2541014336,52.836554246,1828.8 -4.2572481003,52.8314701808,1828.8 -4.2598400991,52.82627262180001,1828.8 -4.2618665826,52.8209837219,1828.8 -4.2633191239,52.81562601520001,1828.8 -4.2641917489,52.8102223209,1828.8 -4.2644809586,52.8047956454,1828.8 -4.2641857397,52.79936908449999,1828.8 -4.263307566,52.7939657248,1828.8 -4.2618503879,52.78860854600001,1828.8 -4.2598206119,52.7833203228,1828.8 -4.2572270704,52.7781235288,1828.8 -4.2540809803,52.7730402409,1828.8 -4.2503958922,52.7680920465,1828.8 -4.2461876305,52.763299952,1828.8 -4.2414742231,52.7586842944,1828.8 -4.236275823,52.75426465569999,1828.8 -4.2306146206,52.7500597804,1828.8 -4.2245147485,52.7460874972,1828.8 -4.2180021779,52.7423646436,1828.8 -4.2111046078,52.7389069959,1828.8 -4.2038513475,52.735729203,1828.8 -4.1962731925,52.73284472500001,1828.8 -4.1884022946,52.7302657772,1828.8 -4.180272027,52.7280032789,1828.8 -4.1719168439,52.7260668081,1828.8 -4.1633721365,52.7244645613,1828.8 -4.1546740851,52.7232033196,1828.8 -4.1458595084,52.7222884205,1828.8 -4.1369657097,52.7217237352,1828.8 -4.1280303217,52.7215116532,1828.8 -4.1190911504,52.7216530717,1828.8 -4.1101860173,52.72214739249999,1828.8 -4.1013526024,52.7229925239,1828.8 -4.0926282873,52.7241848898,1828.8 -4.08405,52.72571944440001,1828.8 -4.086225,52.7713305556,1828.8 -4.0913879573,52.7692223853,1828.8 -4.0968429653,52.76740518580001,1828.8 -4.1025466245,52.76589502910001,1828.8 -4.1084520974,52.7647043103,1828.8 -4.1145109035,52.763842802,1828.8 -4.1206733141,52.763317574,1828.8 -4.1268887576,52.7631329367,1828.8 -4.1331062308,52.76329040510001,1828.8 -4.1392747141,52.76378868689999,1828.8 -4.1453435863,52.7646236933,1828.8 -4.1512630371,52.7657885717,1828.8 -4.1569844719,52.7672737619,1828.8 -4.1624609086,52.7690670735,1828.8 -4.1676473604,52.7711537858,1828.8 -4.1725012037,52.77351676720001,1828.8 -4.1769825268,52.77613661509999,1828.8 -4.1810544573,52.77899181389999,1828.8 -4.1846834655,52.7820589112,1828.8 -4.1878396407,52.7853127087,1828.8 -4.1904969392,52.7887264686,1828.8 -4.1926334009,52.7922721322,1828.8 -4.1942313326,52.7959205499,1828.8 -4.1952774577,52.79964171970001,1828.8 -4.1957630298,52.803405034,1828.8 -4.1956839083,52.8071795305,1828.8 -4.1950405983,52.8109341468,1828.8 -4.1938382505,52.8146379764,1828.8 -4.1920866238,52.818260523,1828.8 -4.1898000094,52.8217719521,1828.8 -4.1869971173,52.82514333729999,1828.8 -4.1837009258,52.8283468994,1828.8 -4.1799384954,52.8313562361,1828.8 -4.1757407482,52.8341465404,1828.8 -4.1711422147,52.8366948064,1828.8 -4.16618075,52.8389800201,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1630888889,52.8850805556,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1716703219,52.88348920120001,609.6 -4.1716703219,52.88348920120001,1828.8 -4.1630888889,52.8850805556,1828.8 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1716703219,52.88348920120001,609.6 -4.1800610524,52.8815618217,609.6 -4.1800610524,52.8815618217,1828.8 -4.1716703219,52.88348920120001,1828.8 -4.1716703219,52.88348920120001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1800610524,52.8815618217,609.6 -4.1882253836,52.879307044,609.6 -4.1882253836,52.879307044,1828.8 -4.1800610524,52.8815618217,1828.8 -4.1800610524,52.8815618217,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1882253836,52.879307044,609.6 -4.1961284314,52.8767345124,609.6 -4.1961284314,52.8767345124,1828.8 -4.1882253836,52.879307044,1828.8 -4.1882253836,52.879307044,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1961284314,52.8767345124,609.6 -4.203736446,52.8738552286,609.6 -4.203736446,52.8738552286,1828.8 -4.1961284314,52.8767345124,1828.8 -4.1961284314,52.8767345124,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.203736446,52.8738552286,609.6 -4.2110169583,52.87068150359999,609.6 -4.2110169583,52.87068150359999,1828.8 -4.203736446,52.8738552286,1828.8 -4.203736446,52.8738552286,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2110169583,52.87068150359999,609.6 -4.2179389192,52.8672269048,609.6 -4.2179389192,52.8672269048,1828.8 -4.2110169583,52.87068150359999,1828.8 -4.2110169583,52.87068150359999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2179389192,52.8672269048,609.6 -4.2244728329,52.8635061966,609.6 -4.2244728329,52.8635061966,1828.8 -4.2179389192,52.8672269048,1828.8 -4.2179389192,52.8672269048,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2244728329,52.8635061966,609.6 -4.2305908832,52.8595352771,609.6 -4.2305908832,52.8595352771,1828.8 -4.2244728329,52.8635061966,1828.8 -4.2244728329,52.8635061966,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2305908832,52.8595352771,609.6 -4.2362670523,52.8553311089,609.6 -4.2362670523,52.8553311089,1828.8 -4.2305908832,52.8595352771,1828.8 -4.2305908832,52.8595352771,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2362670523,52.8553311089,609.6 -4.2414772309,52.8509116461,609.6 -4.2414772309,52.8509116461,1828.8 -4.2362670523,52.8553311089,1828.8 -4.2362670523,52.8553311089,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2414772309,52.8509116461,609.6 -4.24619932,52.8462957566,609.6 -4.24619932,52.8462957566,1828.8 -4.2414772309,52.8509116461,1828.8 -4.2414772309,52.8509116461,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.24619932,52.8462957566,609.6 -4.2504133239,52.8415031405,609.6 -4.2504133239,52.8415031405,1828.8 -4.24619932,52.8462957566,1828.8 -4.24619932,52.8462957566,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2504133239,52.8415031405,609.6 -4.2541014336,52.836554246,609.6 -4.2541014336,52.836554246,1828.8 -4.2504133239,52.8415031405,1828.8 -4.2504133239,52.8415031405,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2541014336,52.836554246,609.6 -4.2572481003,52.8314701808,609.6 -4.2572481003,52.8314701808,1828.8 -4.2541014336,52.836554246,1828.8 -4.2541014336,52.836554246,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2572481003,52.8314701808,609.6 -4.2598400991,52.82627262180001,609.6 -4.2598400991,52.82627262180001,1828.8 -4.2572481003,52.8314701808,1828.8 -4.2572481003,52.8314701808,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2598400991,52.82627262180001,609.6 -4.2618665826,52.8209837219,609.6 -4.2618665826,52.8209837219,1828.8 -4.2598400991,52.82627262180001,1828.8 -4.2598400991,52.82627262180001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2618665826,52.8209837219,609.6 -4.2633191239,52.81562601520001,609.6 -4.2633191239,52.81562601520001,1828.8 -4.2618665826,52.8209837219,1828.8 -4.2618665826,52.8209837219,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2633191239,52.81562601520001,609.6 -4.2641917489,52.8102223209,609.6 -4.2641917489,52.8102223209,1828.8 -4.2633191239,52.81562601520001,1828.8 -4.2633191239,52.81562601520001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2641917489,52.8102223209,609.6 -4.2644809586,52.8047956454,609.6 -4.2644809586,52.8047956454,1828.8 -4.2641917489,52.8102223209,1828.8 -4.2641917489,52.8102223209,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2644809586,52.8047956454,609.6 -4.2641857397,52.79936908449999,609.6 -4.2641857397,52.79936908449999,1828.8 -4.2644809586,52.8047956454,1828.8 -4.2644809586,52.8047956454,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2641857397,52.79936908449999,609.6 -4.263307566,52.7939657248,609.6 -4.263307566,52.7939657248,1828.8 -4.2641857397,52.79936908449999,1828.8 -4.2641857397,52.79936908449999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.263307566,52.7939657248,609.6 -4.2618503879,52.78860854600001,609.6 -4.2618503879,52.78860854600001,1828.8 -4.263307566,52.7939657248,1828.8 -4.263307566,52.7939657248,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2618503879,52.78860854600001,609.6 -4.2598206119,52.7833203228,609.6 -4.2598206119,52.7833203228,1828.8 -4.2618503879,52.78860854600001,1828.8 -4.2618503879,52.78860854600001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2598206119,52.7833203228,609.6 -4.2572270704,52.7781235288,609.6 -4.2572270704,52.7781235288,1828.8 -4.2598206119,52.7833203228,1828.8 -4.2598206119,52.7833203228,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2572270704,52.7781235288,609.6 -4.2540809803,52.7730402409,609.6 -4.2540809803,52.7730402409,1828.8 -4.2572270704,52.7781235288,1828.8 -4.2572270704,52.7781235288,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2540809803,52.7730402409,609.6 -4.2503958922,52.7680920465,609.6 -4.2503958922,52.7680920465,1828.8 -4.2540809803,52.7730402409,1828.8 -4.2540809803,52.7730402409,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2503958922,52.7680920465,609.6 -4.2461876305,52.763299952,609.6 -4.2461876305,52.763299952,1828.8 -4.2503958922,52.7680920465,1828.8 -4.2503958922,52.7680920465,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2461876305,52.763299952,609.6 -4.2414742231,52.7586842944,609.6 -4.2414742231,52.7586842944,1828.8 -4.2461876305,52.763299952,1828.8 -4.2461876305,52.763299952,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2414742231,52.7586842944,609.6 -4.236275823,52.75426465569999,609.6 -4.236275823,52.75426465569999,1828.8 -4.2414742231,52.7586842944,1828.8 -4.2414742231,52.7586842944,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.236275823,52.75426465569999,609.6 -4.2306146206,52.7500597804,609.6 -4.2306146206,52.7500597804,1828.8 -4.236275823,52.75426465569999,1828.8 -4.236275823,52.75426465569999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2306146206,52.7500597804,609.6 -4.2245147485,52.7460874972,609.6 -4.2245147485,52.7460874972,1828.8 -4.2306146206,52.7500597804,1828.8 -4.2306146206,52.7500597804,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2245147485,52.7460874972,609.6 -4.2180021779,52.7423646436,609.6 -4.2180021779,52.7423646436,1828.8 -4.2245147485,52.7460874972,1828.8 -4.2245147485,52.7460874972,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2180021779,52.7423646436,609.6 -4.2111046078,52.7389069959,609.6 -4.2111046078,52.7389069959,1828.8 -4.2180021779,52.7423646436,1828.8 -4.2180021779,52.7423646436,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2111046078,52.7389069959,609.6 -4.2038513475,52.735729203,609.6 -4.2038513475,52.735729203,1828.8 -4.2111046078,52.7389069959,1828.8 -4.2111046078,52.7389069959,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2038513475,52.735729203,609.6 -4.1962731925,52.73284472500001,609.6 -4.1962731925,52.73284472500001,1828.8 -4.2038513475,52.735729203,1828.8 -4.2038513475,52.735729203,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1962731925,52.73284472500001,609.6 -4.1884022946,52.7302657772,609.6 -4.1884022946,52.7302657772,1828.8 -4.1962731925,52.73284472500001,1828.8 -4.1962731925,52.73284472500001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1884022946,52.7302657772,609.6 -4.180272027,52.7280032789,609.6 -4.180272027,52.7280032789,1828.8 -4.1884022946,52.7302657772,1828.8 -4.1884022946,52.7302657772,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.180272027,52.7280032789,609.6 -4.1719168439,52.7260668081,609.6 -4.1719168439,52.7260668081,1828.8 -4.180272027,52.7280032789,1828.8 -4.180272027,52.7280032789,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1719168439,52.7260668081,609.6 -4.1633721365,52.7244645613,609.6 -4.1633721365,52.7244645613,1828.8 -4.1719168439,52.7260668081,1828.8 -4.1719168439,52.7260668081,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1633721365,52.7244645613,609.6 -4.1546740851,52.7232033196,609.6 -4.1546740851,52.7232033196,1828.8 -4.1633721365,52.7244645613,1828.8 -4.1633721365,52.7244645613,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1546740851,52.7232033196,609.6 -4.1458595084,52.7222884205,609.6 -4.1458595084,52.7222884205,1828.8 -4.1546740851,52.7232033196,1828.8 -4.1546740851,52.7232033196,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1458595084,52.7222884205,609.6 -4.1369657097,52.7217237352,609.6 -4.1369657097,52.7217237352,1828.8 -4.1458595084,52.7222884205,1828.8 -4.1458595084,52.7222884205,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1369657097,52.7217237352,609.6 -4.1280303217,52.7215116532,609.6 -4.1280303217,52.7215116532,1828.8 -4.1369657097,52.7217237352,1828.8 -4.1369657097,52.7217237352,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1280303217,52.7215116532,609.6 -4.1190911504,52.7216530717,609.6 -4.1190911504,52.7216530717,1828.8 -4.1280303217,52.7215116532,1828.8 -4.1280303217,52.7215116532,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1190911504,52.7216530717,609.6 -4.1101860173,52.72214739249999,609.6 -4.1101860173,52.72214739249999,1828.8 -4.1190911504,52.7216530717,1828.8 -4.1190911504,52.7216530717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1101860173,52.72214739249999,609.6 -4.1013526024,52.7229925239,609.6 -4.1013526024,52.7229925239,1828.8 -4.1101860173,52.72214739249999,1828.8 -4.1101860173,52.72214739249999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1013526024,52.7229925239,609.6 -4.0926282873,52.7241848898,609.6 -4.0926282873,52.7241848898,1828.8 -4.1013526024,52.7229925239,1828.8 -4.1013526024,52.7229925239,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0926282873,52.7241848898,609.6 -4.08405,52.72571944440001,609.6 -4.08405,52.72571944440001,1828.8 -4.0926282873,52.7241848898,1828.8 -4.0926282873,52.7241848898,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.08405,52.72571944440001,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.08405,52.72571944440001,1828.8 -4.08405,52.72571944440001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0913879573,52.7692223853,609.6 -4.0913879573,52.7692223853,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0913879573,52.7692223853,609.6 -4.0968429653,52.76740518580001,609.6 -4.0968429653,52.76740518580001,1828.8 -4.0913879573,52.7692223853,1828.8 -4.0913879573,52.7692223853,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0968429653,52.76740518580001,609.6 -4.1025466245,52.76589502910001,609.6 -4.1025466245,52.76589502910001,1828.8 -4.0968429653,52.76740518580001,1828.8 -4.0968429653,52.76740518580001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1025466245,52.76589502910001,609.6 -4.1084520974,52.7647043103,609.6 -4.1084520974,52.7647043103,1828.8 -4.1025466245,52.76589502910001,1828.8 -4.1025466245,52.76589502910001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1084520974,52.7647043103,609.6 -4.1145109035,52.763842802,609.6 -4.1145109035,52.763842802,1828.8 -4.1084520974,52.7647043103,1828.8 -4.1084520974,52.7647043103,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1145109035,52.763842802,609.6 -4.1206733141,52.763317574,609.6 -4.1206733141,52.763317574,1828.8 -4.1145109035,52.763842802,1828.8 -4.1145109035,52.763842802,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1206733141,52.763317574,609.6 -4.1268887576,52.7631329367,609.6 -4.1268887576,52.7631329367,1828.8 -4.1206733141,52.763317574,1828.8 -4.1206733141,52.763317574,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1268887576,52.7631329367,609.6 -4.1331062308,52.76329040510001,609.6 -4.1331062308,52.76329040510001,1828.8 -4.1268887576,52.7631329367,1828.8 -4.1268887576,52.7631329367,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1331062308,52.76329040510001,609.6 -4.1392747141,52.76378868689999,609.6 -4.1392747141,52.76378868689999,1828.8 -4.1331062308,52.76329040510001,1828.8 -4.1331062308,52.76329040510001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1392747141,52.76378868689999,609.6 -4.1453435863,52.7646236933,609.6 -4.1453435863,52.7646236933,1828.8 -4.1392747141,52.76378868689999,1828.8 -4.1392747141,52.76378868689999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1453435863,52.7646236933,609.6 -4.1512630371,52.7657885717,609.6 -4.1512630371,52.7657885717,1828.8 -4.1453435863,52.7646236933,1828.8 -4.1453435863,52.7646236933,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1512630371,52.7657885717,609.6 -4.1569844719,52.7672737619,609.6 -4.1569844719,52.7672737619,1828.8 -4.1512630371,52.7657885717,1828.8 -4.1512630371,52.7657885717,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1569844719,52.7672737619,609.6 -4.1624609086,52.7690670735,609.6 -4.1624609086,52.7690670735,1828.8 -4.1569844719,52.7672737619,1828.8 -4.1569844719,52.7672737619,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1624609086,52.7690670735,609.6 -4.1676473604,52.7711537858,609.6 -4.1676473604,52.7711537858,1828.8 -4.1624609086,52.7690670735,1828.8 -4.1624609086,52.7690670735,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1676473604,52.7711537858,609.6 -4.1725012037,52.77351676720001,609.6 -4.1725012037,52.77351676720001,1828.8 -4.1676473604,52.7711537858,1828.8 -4.1676473604,52.7711537858,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1725012037,52.77351676720001,609.6 -4.1769825268,52.77613661509999,609.6 -4.1769825268,52.77613661509999,1828.8 -4.1725012037,52.77351676720001,1828.8 -4.1725012037,52.77351676720001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769825268,52.77613661509999,609.6 -4.1810544573,52.77899181389999,609.6 -4.1810544573,52.77899181389999,1828.8 -4.1769825268,52.77613661509999,1828.8 -4.1769825268,52.77613661509999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1810544573,52.77899181389999,609.6 -4.1846834655,52.7820589112,609.6 -4.1846834655,52.7820589112,1828.8 -4.1810544573,52.77899181389999,1828.8 -4.1810544573,52.77899181389999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1846834655,52.7820589112,609.6 -4.1878396407,52.7853127087,609.6 -4.1878396407,52.7853127087,1828.8 -4.1846834655,52.7820589112,1828.8 -4.1846834655,52.7820589112,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1878396407,52.7853127087,609.6 -4.1904969392,52.7887264686,609.6 -4.1904969392,52.7887264686,1828.8 -4.1878396407,52.7853127087,1828.8 -4.1878396407,52.7853127087,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1904969392,52.7887264686,609.6 -4.1926334009,52.7922721322,609.6 -4.1926334009,52.7922721322,1828.8 -4.1904969392,52.7887264686,1828.8 -4.1904969392,52.7887264686,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1926334009,52.7922721322,609.6 -4.1942313326,52.7959205499,609.6 -4.1942313326,52.7959205499,1828.8 -4.1926334009,52.7922721322,1828.8 -4.1926334009,52.7922721322,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1942313326,52.7959205499,609.6 -4.1952774577,52.79964171970001,609.6 -4.1952774577,52.79964171970001,1828.8 -4.1942313326,52.7959205499,1828.8 -4.1942313326,52.7959205499,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1952774577,52.79964171970001,609.6 -4.1957630298,52.803405034,609.6 -4.1957630298,52.803405034,1828.8 -4.1952774577,52.79964171970001,1828.8 -4.1952774577,52.79964171970001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957630298,52.803405034,609.6 -4.1956839083,52.8071795305,609.6 -4.1956839083,52.8071795305,1828.8 -4.1957630298,52.803405034,1828.8 -4.1957630298,52.803405034,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1956839083,52.8071795305,609.6 -4.1950405983,52.8109341468,609.6 -4.1950405983,52.8109341468,1828.8 -4.1956839083,52.8071795305,1828.8 -4.1956839083,52.8071795305,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1950405983,52.8109341468,609.6 -4.1938382505,52.8146379764,609.6 -4.1938382505,52.8146379764,1828.8 -4.1950405983,52.8109341468,1828.8 -4.1950405983,52.8109341468,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1938382505,52.8146379764,609.6 -4.1920866238,52.818260523,609.6 -4.1920866238,52.818260523,1828.8 -4.1938382505,52.8146379764,1828.8 -4.1938382505,52.8146379764,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1920866238,52.818260523,609.6 -4.1898000094,52.8217719521,609.6 -4.1898000094,52.8217719521,1828.8 -4.1920866238,52.818260523,1828.8 -4.1920866238,52.818260523,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1898000094,52.8217719521,609.6 -4.1869971173,52.82514333729999,609.6 -4.1869971173,52.82514333729999,1828.8 -4.1898000094,52.8217719521,1828.8 -4.1898000094,52.8217719521,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1869971173,52.82514333729999,609.6 -4.1837009258,52.8283468994,609.6 -4.1837009258,52.8283468994,1828.8 -4.1869971173,52.82514333729999,1828.8 -4.1869971173,52.82514333729999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1837009258,52.8283468994,609.6 -4.1799384954,52.8313562361,609.6 -4.1799384954,52.8313562361,1828.8 -4.1837009258,52.8283468994,1828.8 -4.1837009258,52.8283468994,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1799384954,52.8313562361,609.6 -4.1757407482,52.8341465404,609.6 -4.1757407482,52.8341465404,1828.8 -4.1799384954,52.8313562361,1828.8 -4.1799384954,52.8313562361,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1757407482,52.8341465404,609.6 -4.1711422147,52.8366948064,609.6 -4.1711422147,52.8366948064,1828.8 -4.1757407482,52.8341465404,1828.8 -4.1757407482,52.8341465404,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1711422147,52.8366948064,609.6 -4.16618075,52.8389800201,609.6 -4.16618075,52.8389800201,1828.8 -4.1711422147,52.8366948064,1828.8 -4.1711422147,52.8366948064,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.16618075,52.8389800201,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8 -4.16618075,52.8389800201,1828.8 -4.16618075,52.8389800201,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1608972222,52.8409833333,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1608972222,52.8409833333,609.6 + + + + + +
+ + EGD217I LLANBEDR + 524942N 0041102W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
524617N 0040510W -
524603N 0040510W -
523933N 0041231W -
524222N 0041917W -
524942N 0041102W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.2084722222,52.6592083333,1828.8 -4.0860444444,52.7675166667,1828.8 -4.086225,52.7713305556,1828.8 -4.0913798344,52.76921870109999,1828.8 -4.0968320407,52.7674020804,1828.8 -4.1025326866,52.76589215620001,1828.8 -4.1084350162,52.76470130689999,1828.8 -4.1144906333,52.76383929410001,1828.8 -4.1206498956,52.7633131834,1828.8 -4.1268623184,52.76312728700001,1828.8 -4.1330769853,52.7632831285,1828.8 -4.1392429612,52.7637794307,1828.8 -4.145309707,52.7646121256,1828.8 -4.1512274901,52.7657743881,1828.8 -4.1569477885,52.7672566908,1828.8 -4.1624236863,52.7690468821,1828.8 -4.167610256,52.7711302844,1828.8 -4.1724649246,52.7734898141,1828.8 -4.1769478222,52.7761061204,1828.8 -4.1810221083,52.7789577431,1828.8 -4.1846542748,52.7820212872,1828.8 -4.1878144214,52.7852716143,1828.8 -4.1904765038,52.7886820476,1828.8 -4.1926185491,52.7922245896,1828.8 -4.1942228402,52.7958701517,1828.8 -4.1952760644,52.799588792,1828.8 -4.1957694276,52.8033499607,1828.8 -4.1956987304,52.8071227506,1828.8 -4.195064408,52.81087615129999,1828.8 -4.193871531,52.8145793036,1828.8 -4.1921297686,52.81820175400001,1828.8 -4.1898533133,52.8217137049,1828.8 -4.1870607687,52.82508626089999,1828.8 -4.183775,52.8282916667,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.183775,52.8282916667,609.6 -4.3215111111,52.70620277780001,609.6 -4.3215111111,52.70620277780001,1828.8 -4.183775,52.8282916667,1828.8 -4.183775,52.8282916667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.3215111111,52.70620277780001,609.6 -4.2084722222,52.6592083333,609.6 -4.2084722222,52.6592083333,1828.8 -4.3215111111,52.70620277780001,1828.8 -4.3215111111,52.70620277780001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.2084722222,52.6592083333,609.6 -4.0860444444,52.7675166667,609.6 -4.0860444444,52.7675166667,1828.8 -4.2084722222,52.6592083333,1828.8 -4.2084722222,52.6592083333,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0860444444,52.7675166667,609.6 -4.086225,52.7713305556,609.6 -4.086225,52.7713305556,1828.8 -4.0860444444,52.7675166667,1828.8 -4.0860444444,52.7675166667,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.086225,52.7713305556,609.6 -4.0913798344,52.76921870109999,609.6 -4.0913798344,52.76921870109999,1828.8 -4.086225,52.7713305556,1828.8 -4.086225,52.7713305556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0913798344,52.76921870109999,609.6 -4.0968320407,52.7674020804,609.6 -4.0968320407,52.7674020804,1828.8 -4.0913798344,52.76921870109999,1828.8 -4.0913798344,52.76921870109999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0968320407,52.7674020804,609.6 -4.1025326866,52.76589215620001,609.6 -4.1025326866,52.76589215620001,1828.8 -4.0968320407,52.7674020804,1828.8 -4.0968320407,52.7674020804,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1025326866,52.76589215620001,609.6 -4.1084350162,52.76470130689999,609.6 -4.1084350162,52.76470130689999,1828.8 -4.1025326866,52.76589215620001,1828.8 -4.1025326866,52.76589215620001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1084350162,52.76470130689999,609.6 -4.1144906333,52.76383929410001,609.6 -4.1144906333,52.76383929410001,1828.8 -4.1084350162,52.76470130689999,1828.8 -4.1084350162,52.76470130689999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1144906333,52.76383929410001,609.6 -4.1206498956,52.7633131834,609.6 -4.1206498956,52.7633131834,1828.8 -4.1144906333,52.76383929410001,1828.8 -4.1144906333,52.76383929410001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1206498956,52.7633131834,609.6 -4.1268623184,52.76312728700001,609.6 -4.1268623184,52.76312728700001,1828.8 -4.1206498956,52.7633131834,1828.8 -4.1206498956,52.7633131834,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1268623184,52.76312728700001,609.6 -4.1330769853,52.7632831285,609.6 -4.1330769853,52.7632831285,1828.8 -4.1268623184,52.76312728700001,1828.8 -4.1268623184,52.76312728700001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1330769853,52.7632831285,609.6 -4.1392429612,52.7637794307,609.6 -4.1392429612,52.7637794307,1828.8 -4.1330769853,52.7632831285,1828.8 -4.1330769853,52.7632831285,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1392429612,52.7637794307,609.6 -4.145309707,52.7646121256,609.6 -4.145309707,52.7646121256,1828.8 -4.1392429612,52.7637794307,1828.8 -4.1392429612,52.7637794307,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.145309707,52.7646121256,609.6 -4.1512274901,52.7657743881,609.6 -4.1512274901,52.7657743881,1828.8 -4.145309707,52.7646121256,1828.8 -4.145309707,52.7646121256,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1512274901,52.7657743881,609.6 -4.1569477885,52.7672566908,609.6 -4.1569477885,52.7672566908,1828.8 -4.1512274901,52.7657743881,1828.8 -4.1512274901,52.7657743881,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1569477885,52.7672566908,609.6 -4.1624236863,52.7690468821,609.6 -4.1624236863,52.7690468821,1828.8 -4.1569477885,52.7672566908,1828.8 -4.1569477885,52.7672566908,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1624236863,52.7690468821,609.6 -4.167610256,52.7711302844,609.6 -4.167610256,52.7711302844,1828.8 -4.1624236863,52.7690468821,1828.8 -4.1624236863,52.7690468821,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.167610256,52.7711302844,609.6 -4.1724649246,52.7734898141,609.6 -4.1724649246,52.7734898141,1828.8 -4.167610256,52.7711302844,1828.8 -4.167610256,52.7711302844,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1724649246,52.7734898141,609.6 -4.1769478222,52.7761061204,609.6 -4.1769478222,52.7761061204,1828.8 -4.1724649246,52.7734898141,1828.8 -4.1724649246,52.7734898141,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1769478222,52.7761061204,609.6 -4.1810221083,52.7789577431,609.6 -4.1810221083,52.7789577431,1828.8 -4.1769478222,52.7761061204,1828.8 -4.1769478222,52.7761061204,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1810221083,52.7789577431,609.6 -4.1846542748,52.7820212872,609.6 -4.1846542748,52.7820212872,1828.8 -4.1810221083,52.7789577431,1828.8 -4.1810221083,52.7789577431,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1846542748,52.7820212872,609.6 -4.1878144214,52.7852716143,609.6 -4.1878144214,52.7852716143,1828.8 -4.1846542748,52.7820212872,1828.8 -4.1846542748,52.7820212872,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1878144214,52.7852716143,609.6 -4.1904765038,52.7886820476,609.6 -4.1904765038,52.7886820476,1828.8 -4.1878144214,52.7852716143,1828.8 -4.1878144214,52.7852716143,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1904765038,52.7886820476,609.6 -4.1926185491,52.7922245896,609.6 -4.1926185491,52.7922245896,1828.8 -4.1904765038,52.7886820476,1828.8 -4.1904765038,52.7886820476,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1926185491,52.7922245896,609.6 -4.1942228402,52.7958701517,609.6 -4.1942228402,52.7958701517,1828.8 -4.1926185491,52.7922245896,1828.8 -4.1926185491,52.7922245896,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1942228402,52.7958701517,609.6 -4.1952760644,52.799588792,609.6 -4.1952760644,52.799588792,1828.8 -4.1942228402,52.7958701517,1828.8 -4.1942228402,52.7958701517,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1952760644,52.799588792,609.6 -4.1957694276,52.8033499607,609.6 -4.1957694276,52.8033499607,1828.8 -4.1952760644,52.799588792,1828.8 -4.1952760644,52.799588792,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1957694276,52.8033499607,609.6 -4.1956987304,52.8071227506,609.6 -4.1956987304,52.8071227506,1828.8 -4.1957694276,52.8033499607,1828.8 -4.1957694276,52.8033499607,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1956987304,52.8071227506,609.6 -4.195064408,52.81087615129999,609.6 -4.195064408,52.81087615129999,1828.8 -4.1956987304,52.8071227506,1828.8 -4.1956987304,52.8071227506,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.195064408,52.81087615129999,609.6 -4.193871531,52.8145793036,609.6 -4.193871531,52.8145793036,1828.8 -4.195064408,52.81087615129999,1828.8 -4.195064408,52.81087615129999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.193871531,52.8145793036,609.6 -4.1921297686,52.81820175400001,609.6 -4.1921297686,52.81820175400001,1828.8 -4.193871531,52.8145793036,1828.8 -4.193871531,52.8145793036,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1921297686,52.81820175400001,609.6 -4.1898533133,52.8217137049,609.6 -4.1898533133,52.8217137049,1828.8 -4.1921297686,52.81820175400001,1828.8 -4.1921297686,52.81820175400001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1898533133,52.8217137049,609.6 -4.1870607687,52.82508626089999,609.6 -4.1870607687,52.82508626089999,1828.8 -4.1898533133,52.8217137049,1828.8 -4.1898533133,52.8217137049,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1870607687,52.82508626089999,609.6 -4.183775,52.8282916667,609.6 -4.183775,52.8282916667,1828.8 -4.1870607687,52.82508626089999,1828.8 -4.1870607687,52.82508626089999,609.6 + + + + + +
+ + EGD217J LLANBEDR + 525307N 0040530W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
524333N 0040503W -
525307N 0040530W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,1828.8 -4.08405,52.72571944440001,1828.8 -4.0755987733,52.7276026422,1828.8 -4.0673688901,52.7298184726,1828.8 -4.0593953848,52.7323568761,1828.8 -4.0517125112,52.7352069624,1828.8 -4.0443532948,52.738356502,1828.8 -4.037349392,52.7417919777,1828.8 -4.030730955,52.7454986418,1828.8 -4.0245265029,52.7494605784,1828.8 -4.0187627984,52.7536607714,1828.8 -4.0134647331,52.75808117619999,1828.8 -4.0086552188,52.7627027967,1828.8 -4.0043550877,52.7675057658,1828.8 -4.0005830012,52.7724694303,1828.8 -3.9973553675,52.7775724392,1828.8 -3.9946862679,52.78279283410001,1828.8 -3.9925873936,52.7881081439,1828.8 -3.9910679921,52.79349548079999,1828.8 -3.9901348241,52.7989316381,1828.8 -3.989792130500001,52.80439319039999,1828.8 -3.9900416104,52.8098565941,1828.8 -3.990882410299999,52.8152982887,1828.8 -3.9923111235,52.8206947986,1828.8 -3.9943218012,52.8260228348,1828.8 -3.9969059746,52.831259395,1828.8 -4.0000526878,52.8363818638,1828.8 -4.0037485419,52.8413681109,1828.8 -4.0079777498,52.8461965867,1828.8 -4.0127222017,52.85084641669999,1828.8 -4.0179615407,52.8552974922,1828.8 -4.0236732496,52.8595305579,1828.8 -4.0298327457,52.8635272962,1828.8 -4.0364134868,52.8672704074,1828.8 -4.0433870849,52.8707436851,1828.8 -4.0507234291,52.8739320877,1828.8 -4.0583908159,52.8768218039,1828.8 -4.0663560872,52.8794003139,1828.8 -4.0745847751,52.8816564439,1828.8 -4.0830412523,52.8835804155,1828.8 -4.0916888889,52.8851638889,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.08405,52.72571944440001,609.6 -4.08405,52.72571944440001,1828.8 -4.0916888889,52.8851638889,1828.8 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.08405,52.72571944440001,609.6 -4.0755987733,52.7276026422,609.6 -4.0755987733,52.7276026422,1828.8 -4.08405,52.72571944440001,1828.8 -4.08405,52.72571944440001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0755987733,52.7276026422,609.6 -4.0673688901,52.7298184726,609.6 -4.0673688901,52.7298184726,1828.8 -4.0755987733,52.7276026422,1828.8 -4.0755987733,52.7276026422,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0673688901,52.7298184726,609.6 -4.0593953848,52.7323568761,609.6 -4.0593953848,52.7323568761,1828.8 -4.0673688901,52.7298184726,1828.8 -4.0673688901,52.7298184726,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0593953848,52.7323568761,609.6 -4.0517125112,52.7352069624,609.6 -4.0517125112,52.7352069624,1828.8 -4.0593953848,52.7323568761,1828.8 -4.0593953848,52.7323568761,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0517125112,52.7352069624,609.6 -4.0443532948,52.738356502,609.6 -4.0443532948,52.738356502,1828.8 -4.0517125112,52.7352069624,1828.8 -4.0517125112,52.7352069624,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0443532948,52.738356502,609.6 -4.037349392,52.7417919777,609.6 -4.037349392,52.7417919777,1828.8 -4.0443532948,52.738356502,1828.8 -4.0443532948,52.738356502,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.037349392,52.7417919777,609.6 -4.030730955,52.7454986418,609.6 -4.030730955,52.7454986418,1828.8 -4.037349392,52.7417919777,1828.8 -4.037349392,52.7417919777,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.030730955,52.7454986418,609.6 -4.0245265029,52.7494605784,609.6 -4.0245265029,52.7494605784,1828.8 -4.030730955,52.7454986418,1828.8 -4.030730955,52.7454986418,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0245265029,52.7494605784,609.6 -4.0187627984,52.7536607714,609.6 -4.0187627984,52.7536607714,1828.8 -4.0245265029,52.7494605784,1828.8 -4.0245265029,52.7494605784,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0187627984,52.7536607714,609.6 -4.0134647331,52.75808117619999,609.6 -4.0134647331,52.75808117619999,1828.8 -4.0187627984,52.7536607714,1828.8 -4.0187627984,52.7536607714,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0134647331,52.75808117619999,609.6 -4.0086552188,52.7627027967,609.6 -4.0086552188,52.7627027967,1828.8 -4.0134647331,52.75808117619999,1828.8 -4.0134647331,52.75808117619999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0086552188,52.7627027967,609.6 -4.0043550877,52.7675057658,609.6 -4.0043550877,52.7675057658,1828.8 -4.0086552188,52.7627027967,1828.8 -4.0086552188,52.7627027967,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0043550877,52.7675057658,609.6 -4.0005830012,52.7724694303,609.6 -4.0005830012,52.7724694303,1828.8 -4.0043550877,52.7675057658,1828.8 -4.0043550877,52.7675057658,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0005830012,52.7724694303,609.6 -3.9973553675,52.7775724392,609.6 -3.9973553675,52.7775724392,1828.8 -4.0005830012,52.7724694303,1828.8 -4.0005830012,52.7724694303,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9973553675,52.7775724392,609.6 -3.9946862679,52.78279283410001,609.6 -3.9946862679,52.78279283410001,1828.8 -3.9973553675,52.7775724392,1828.8 -3.9973553675,52.7775724392,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9946862679,52.78279283410001,609.6 -3.9925873936,52.7881081439,609.6 -3.9925873936,52.7881081439,1828.8 -3.9946862679,52.78279283410001,1828.8 -3.9946862679,52.78279283410001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9925873936,52.7881081439,609.6 -3.9910679921,52.79349548079999,609.6 -3.9910679921,52.79349548079999,1828.8 -3.9925873936,52.7881081439,1828.8 -3.9925873936,52.7881081439,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9910679921,52.79349548079999,609.6 -3.9901348241,52.7989316381,609.6 -3.9901348241,52.7989316381,1828.8 -3.9910679921,52.79349548079999,1828.8 -3.9910679921,52.79349548079999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9901348241,52.7989316381,609.6 -3.989792130500001,52.80439319039999,609.6 -3.989792130500001,52.80439319039999,1828.8 -3.9901348241,52.7989316381,1828.8 -3.9901348241,52.7989316381,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.989792130500001,52.80439319039999,609.6 -3.9900416104,52.8098565941,609.6 -3.9900416104,52.8098565941,1828.8 -3.989792130500001,52.80439319039999,1828.8 -3.989792130500001,52.80439319039999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9900416104,52.8098565941,609.6 -3.990882410299999,52.8152982887,609.6 -3.990882410299999,52.8152982887,1828.8 -3.9900416104,52.8098565941,1828.8 -3.9900416104,52.8098565941,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.990882410299999,52.8152982887,609.6 -3.9923111235,52.8206947986,609.6 -3.9923111235,52.8206947986,1828.8 -3.990882410299999,52.8152982887,1828.8 -3.990882410299999,52.8152982887,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9923111235,52.8206947986,609.6 -3.9943218012,52.8260228348,609.6 -3.9943218012,52.8260228348,1828.8 -3.9923111235,52.8206947986,1828.8 -3.9923111235,52.8206947986,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9943218012,52.8260228348,609.6 -3.9969059746,52.831259395,609.6 -3.9969059746,52.831259395,1828.8 -3.9943218012,52.8260228348,1828.8 -3.9943218012,52.8260228348,609.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9969059746,52.831259395,609.6 -4.0000526878,52.8363818638,609.6 -4.0000526878,52.8363818638,1828.8 -3.9969059746,52.831259395,1828.8 -3.9969059746,52.831259395,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0000526878,52.8363818638,609.6 -4.0037485419,52.8413681109,609.6 -4.0037485419,52.8413681109,1828.8 -4.0000526878,52.8363818638,1828.8 -4.0000526878,52.8363818638,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0037485419,52.8413681109,609.6 -4.0079777498,52.8461965867,609.6 -4.0079777498,52.8461965867,1828.8 -4.0037485419,52.8413681109,1828.8 -4.0037485419,52.8413681109,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0079777498,52.8461965867,609.6 -4.0127222017,52.85084641669999,609.6 -4.0127222017,52.85084641669999,1828.8 -4.0079777498,52.8461965867,1828.8 -4.0079777498,52.8461965867,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0127222017,52.85084641669999,609.6 -4.0179615407,52.8552974922,609.6 -4.0179615407,52.8552974922,1828.8 -4.0127222017,52.85084641669999,1828.8 -4.0127222017,52.85084641669999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0179615407,52.8552974922,609.6 -4.0236732496,52.8595305579,609.6 -4.0236732496,52.8595305579,1828.8 -4.0179615407,52.8552974922,1828.8 -4.0179615407,52.8552974922,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0236732496,52.8595305579,609.6 -4.0298327457,52.8635272962,609.6 -4.0298327457,52.8635272962,1828.8 -4.0236732496,52.8595305579,1828.8 -4.0236732496,52.8595305579,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0298327457,52.8635272962,609.6 -4.0364134868,52.8672704074,609.6 -4.0364134868,52.8672704074,1828.8 -4.0298327457,52.8635272962,1828.8 -4.0298327457,52.8635272962,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0364134868,52.8672704074,609.6 -4.0433870849,52.8707436851,609.6 -4.0433870849,52.8707436851,1828.8 -4.0364134868,52.8672704074,1828.8 -4.0364134868,52.8672704074,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0433870849,52.8707436851,609.6 -4.0507234291,52.8739320877,609.6 -4.0507234291,52.8739320877,1828.8 -4.0433870849,52.8707436851,1828.8 -4.0433870849,52.8707436851,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0507234291,52.8739320877,609.6 -4.0583908159,52.8768218039,609.6 -4.0583908159,52.8768218039,1828.8 -4.0507234291,52.8739320877,1828.8 -4.0507234291,52.8739320877,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0583908159,52.8768218039,609.6 -4.0663560872,52.8794003139,609.6 -4.0663560872,52.8794003139,1828.8 -4.0583908159,52.8768218039,1828.8 -4.0583908159,52.8768218039,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0663560872,52.8794003139,609.6 -4.0745847751,52.8816564439,609.6 -4.0745847751,52.8816564439,1828.8 -4.0663560872,52.8794003139,1828.8 -4.0663560872,52.8794003139,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0745847751,52.8816564439,609.6 -4.0830412523,52.8835804155,609.6 -4.0830412523,52.8835804155,1828.8 -4.0745847751,52.8816564439,1828.8 -4.0745847751,52.8816564439,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0830412523,52.8835804155,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8 -4.0830412523,52.8835804155,1828.8 -4.0830412523,52.8835804155,609.6 + + + + + +
+ + EGD217K LLANBEDR + 525306N 0040947W thence clockwise by the arc of a circle radius 5 NM centred on 524817N 0040738W to
525307N 0040530W -
525022N 0040522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524817N 0040738W to
525028N 0040939W -
525306N 0040947W
Upper limit: 6000 FT MSL
Lower limit: 2000 FT MSL
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Test and Evaluation.

Service: SUAAIS Llanbedr Information on 118.930 MHz.

Contact: Llanbedr Information, Tel: 01341-241356.

Danger Area Authority: Snowdonia Aerospace.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1553132526,52.8426949429,1828.8 -4.149494417,52.8440909498,1828.8 -4.143489638,52.8451603374,1828.8 -4.1373488445,52.8458942118,1828.8 -4.131123106,52.84628646940001,1828.8 -4.1248642045,52.8463338475,1828.8 -4.1186242003,52.8460359521,1828.8 -4.1124549952,52.8453952609,1828.8 -4.1064078968,52.8444171027,1828.8 -4.100533189,52.8431096128,1828.8 -4.0948797102,52.8414836643,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0916888889,52.8851638889,1828.8 -4.1004821132,52.88639803100001,1828.8 -4.1093902725,52.8872810751,1828.8 -4.118375237,52.8878082526,1828.8 -4.1273981205,52.88797728189999,1828.8 -4.13641987,52.8877874313,1828.8 -4.1454014374,52.88723952270001,1828.8 -4.1543039514,52.8863359272,1828.8 -4.1630888889,52.8850805556,1828.8 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1630888889,52.8850805556,609.6 -4.1608972222,52.8409833333,609.6 -4.1608972222,52.8409833333,1828.8 -4.1630888889,52.8850805556,1828.8 -4.1630888889,52.8850805556,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1608972222,52.8409833333,609.6 -4.1553132526,52.8426949429,609.6 -4.1553132526,52.8426949429,1828.8 -4.1608972222,52.8409833333,1828.8 -4.1608972222,52.8409833333,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1553132526,52.8426949429,609.6 -4.149494417,52.8440909498,609.6 -4.149494417,52.8440909498,1828.8 -4.1553132526,52.8426949429,1828.8 -4.1553132526,52.8426949429,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.149494417,52.8440909498,609.6 -4.143489638,52.8451603374,609.6 -4.143489638,52.8451603374,1828.8 -4.149494417,52.8440909498,1828.8 -4.149494417,52.8440909498,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.143489638,52.8451603374,609.6 -4.1373488445,52.8458942118,609.6 -4.1373488445,52.8458942118,1828.8 -4.143489638,52.8451603374,1828.8 -4.143489638,52.8451603374,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1373488445,52.8458942118,609.6 -4.131123106,52.84628646940001,609.6 -4.131123106,52.84628646940001,1828.8 -4.1373488445,52.8458942118,1828.8 -4.1373488445,52.8458942118,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.131123106,52.84628646940001,609.6 -4.1248642045,52.8463338475,609.6 -4.1248642045,52.8463338475,1828.8 -4.131123106,52.84628646940001,1828.8 -4.131123106,52.84628646940001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1248642045,52.8463338475,609.6 -4.1186242003,52.8460359521,609.6 -4.1186242003,52.8460359521,1828.8 -4.1248642045,52.8463338475,1828.8 -4.1248642045,52.8463338475,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1186242003,52.8460359521,609.6 -4.1124549952,52.8453952609,609.6 -4.1124549952,52.8453952609,1828.8 -4.1186242003,52.8460359521,1828.8 -4.1186242003,52.8460359521,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1124549952,52.8453952609,609.6 -4.1064078968,52.8444171027,609.6 -4.1064078968,52.8444171027,1828.8 -4.1124549952,52.8453952609,1828.8 -4.1124549952,52.8453952609,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1064078968,52.8444171027,609.6 -4.100533189,52.8431096128,609.6 -4.100533189,52.8431096128,1828.8 -4.1064078968,52.8444171027,1828.8 -4.1064078968,52.8444171027,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.100533189,52.8431096128,609.6 -4.0948797102,52.8414836643,609.6 -4.0948797102,52.8414836643,1828.8 -4.100533189,52.8431096128,1828.8 -4.100533189,52.8431096128,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0948797102,52.8414836643,609.6 -4.0894944444,52.8395527778,609.6 -4.0894944444,52.8395527778,1828.8 -4.0948797102,52.8414836643,1828.8 -4.0948797102,52.8414836643,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0894944444,52.8395527778,609.6 -4.0916888889,52.8851638889,609.6 -4.0916888889,52.8851638889,1828.8 -4.0894944444,52.8395527778,1828.8 -4.0894944444,52.8395527778,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.0916888889,52.8851638889,609.6 -4.1004821132,52.88639803100001,609.6 -4.1004821132,52.88639803100001,1828.8 -4.0916888889,52.8851638889,1828.8 -4.0916888889,52.8851638889,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1004821132,52.88639803100001,609.6 -4.1093902725,52.8872810751,609.6 -4.1093902725,52.8872810751,1828.8 -4.1004821132,52.88639803100001,1828.8 -4.1004821132,52.88639803100001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1093902725,52.8872810751,609.6 -4.118375237,52.8878082526,609.6 -4.118375237,52.8878082526,1828.8 -4.1093902725,52.8872810751,1828.8 -4.1093902725,52.8872810751,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.118375237,52.8878082526,609.6 -4.1273981205,52.88797728189999,609.6 -4.1273981205,52.88797728189999,1828.8 -4.118375237,52.8878082526,1828.8 -4.118375237,52.8878082526,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1273981205,52.88797728189999,609.6 -4.13641987,52.8877874313,609.6 -4.13641987,52.8877874313,1828.8 -4.1273981205,52.88797728189999,1828.8 -4.1273981205,52.88797728189999,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.13641987,52.8877874313,609.6 -4.1454014374,52.88723952270001,609.6 -4.1454014374,52.88723952270001,1828.8 -4.13641987,52.8877874313,1828.8 -4.13641987,52.8877874313,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1454014374,52.88723952270001,609.6 -4.1543039514,52.8863359272,609.6 -4.1543039514,52.8863359272,1828.8 -4.1454014374,52.88723952270001,1828.8 -4.1454014374,52.88723952270001,609.6 + + + + + + relativeToGround + + + relativeToGround + + -4.1543039514,52.8863359272,609.6 -4.1630888889,52.8850805556,609.6 -4.1630888889,52.8850805556,1828.8 -4.1543039514,52.8863359272,1828.8 -4.1543039514,52.8863359272,609.6 + + + + + +
+ + EGD218A FAIRFORD + 514815N 0013543W -
514016N 0013518W -
513958N 0014917W -
514110N 0015928W -
514744N 0015952W -
514815N 0013543W
Upper limit: FL75
Lower limit: SFC
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Brize Radar on 124.275 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5951848611,51.80407725,2286 -1.9976505556,51.79551097220001,2286 -1.9911186944,51.6860482222,2286 -1.8215250833,51.6661864444,2286 -1.58842725,51.6709806111,2286 -1.5951848611,51.80407725,2286 + + + + +
+ + EGD218B FAIRFORD + 520518N 0020404W -
514803N 0014539W -
514749N 0015601W -
514901N 0020407W -
515342N 0022132W -
520518N 0020404W
Upper limit: FL240
Lower limit: FL50
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Below FL160 Brize Radar on 124.275 MHz. At/above FL160 Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,7315.199999999999 -2.3588221389,51.8948650833,7315.199999999999 -2.0686747222,51.8169415833,7315.199999999999 -1.9337063889,51.79696427779999,7315.199999999999 -1.76084275,51.8007185,7315.199999999999 -2.0679103333,52.0883218333,7315.199999999999 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,1524 -2.3588221389,51.8948650833,1524 -2.0686747222,51.8169415833,1524 -1.9337063889,51.79696427779999,1524 -1.76084275,51.8007185,1524 -2.0679103333,52.0883218333,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,1524 -2.3588221389,51.8948650833,1524 -2.3588221389,51.8948650833,7315.199999999999 -2.0679103333,52.0883218333,7315.199999999999 -2.0679103333,52.0883218333,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.3588221389,51.8948650833,1524 -2.0686747222,51.8169415833,1524 -2.0686747222,51.8169415833,7315.199999999999 -2.3588221389,51.8948650833,7315.199999999999 -2.3588221389,51.8948650833,1524 + + + + + + relativeToGround + + + relativeToGround + + -2.0686747222,51.8169415833,1524 -1.9337063889,51.79696427779999,1524 -1.9337063889,51.79696427779999,7315.199999999999 -2.0686747222,51.8169415833,7315.199999999999 -2.0686747222,51.8169415833,1524 + + + + + + relativeToGround + + + relativeToGround + + -1.9337063889,51.79696427779999,1524 -1.76084275,51.8007185,1524 -1.76084275,51.8007185,7315.199999999999 -1.9337063889,51.79696427779999,7315.199999999999 -1.9337063889,51.79696427779999,1524 + + + + + + relativeToGround + + + relativeToGround + + -1.76084275,51.8007185,1524 -2.0679103333,52.0883218333,1524 -2.0679103333,52.0883218333,7315.199999999999 -1.76084275,51.8007185,7315.199999999999 -1.76084275,51.8007185,1524 + + + + + +
+ + EGD218C FAIRFORD + 521533N 0021510W -
520518N 0020404W -
515342N 0022132W -
515701N 0023402W -
520117N 0023842W -
521533N 0021510W
Upper limit: FL660
Lower limit: FL160
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.567252,51.9502352778,20116.8 -2.3588221389,51.8948650833,20116.8 -2.0679103333,52.0883218333,20116.8 -2.2526999167,52.25927605559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,4876.8 -2.6449074167,52.02142933329999,4876.8 -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.25927605559999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,4876.8 -2.6449074167,52.02142933329999,4876.8 -2.6449074167,52.02142933329999,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.2526999167,52.25927605559999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.6449074167,52.02142933329999,4876.8 -2.567252,51.9502352778,4876.8 -2.567252,51.9502352778,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.6449074167,52.02142933329999,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.567252,51.9502352778,4876.8 -2.3588221389,51.8948650833,4876.8 -2.3588221389,51.8948650833,20116.8 -2.567252,51.9502352778,20116.8 -2.567252,51.9502352778,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.3588221389,51.8948650833,4876.8 -2.0679103333,52.0883218333,4876.8 -2.0679103333,52.0883218333,20116.8 -2.3588221389,51.8948650833,20116.8 -2.3588221389,51.8948650833,4876.8 + + + + + + relativeToGround + + + relativeToGround + + -2.0679103333,52.0883218333,4876.8 -2.2526999167,52.25927605559999,4876.8 -2.2526999167,52.25927605559999,20116.8 -2.0679103333,52.0883218333,20116.8 -2.0679103333,52.0883218333,4876.8 + + + + + +
+ + EGD218D FAIRFORD + 523258N 0023414W -
521533N 0021510W -
520117N 0023842W -
521342N 0025221W -
522607N 0025118W -
523258N 0023414W
Upper limit: FL660
Lower limit: FL200
Class: AMC - Manageable.

Activity: Unmanned Aircraft System Beyond Visual Line Of Sight with an Indicated Airspeed (IAS) of 150 KTS or less (BVLOS less than 150 KTS).

Service: SUACS: Swanwick Mil on 128.700 MHz. SUAAIS: London Information on 124.750 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8724085833,52.2284006944,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.5705153611,52.5495711667,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,6096 -2.8549897222,52.4352228333,6096 -2.8724085833,52.2284006944,6096 -2.6449074167,52.02142933329999,6096 -2.2526999167,52.25927605559999,6096 -2.5705153611,52.5495711667,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.5705153611,52.5495711667,6096 -2.8549897222,52.4352228333,6096 -2.8549897222,52.4352228333,20116.8 -2.5705153611,52.5495711667,20116.8 -2.5705153611,52.5495711667,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.8549897222,52.4352228333,6096 -2.8724085833,52.2284006944,6096 -2.8724085833,52.2284006944,20116.8 -2.8549897222,52.4352228333,20116.8 -2.8549897222,52.4352228333,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.8724085833,52.2284006944,6096 -2.6449074167,52.02142933329999,6096 -2.6449074167,52.02142933329999,20116.8 -2.8724085833,52.2284006944,20116.8 -2.8724085833,52.2284006944,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.6449074167,52.02142933329999,6096 -2.2526999167,52.25927605559999,6096 -2.2526999167,52.25927605559999,20116.8 -2.6449074167,52.02142933329999,20116.8 -2.6449074167,52.02142933329999,6096 + + + + + + relativeToGround + + + relativeToGround + + -2.2526999167,52.25927605559999,6096 -2.5705153611,52.5495711667,6096 -2.5705153611,52.5495711667,20116.8 -2.2526999167,52.25927605559999,20116.8 -2.2526999167,52.25927605559999,6096 + + + + + +
+ + EGD304 UPPER HULME + A circle, 1.5 NM radius, centred at 530951N 0015730W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Manchester APP on 118.580 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01785-763134.

Remarks: SI 1985/1082.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9583333333,53.1891285695,1066.8 -1.9632487194,53.1889532633,1066.8 -1.9680949854,53.1884298098,1066.8 -1.9728039882,53.1875655697,1066.8 -1.9773095245,53.1863726948,1066.8 -1.9815482657,53.1848679569,1066.8 -1.9854606515,53.1830725106,1066.8 -1.9889917292,53.1810115942,1066.8 -1.9920919267,53.1787141743,1066.8 -1.994717749,53.1762125364,1066.8 -1.9968323868,53.1735418303,1066.8 -1.9984062307,53.1707395745,1066.8 -1.9994172825,53.1678451281,1066.8 -1.9998514587,53.1648991371,1066.8 -1.9997027821,53.1619429631,1066.8 -1.9989734591,53.15901810199999,1066.8 -1.9976738419,53.15616560210001,1066.8 -1.995822277,53.1534254881,1066.8 -1.9934448418,53.1508362003,1066.8 -1.990574974,53.14843405639999,1066.8 -1.9872529981,53.14625274370001,1066.8 -1.983525558,53.1443228474,1066.8 -1.9794449609,53.1426714238,1066.8 -1.9750684446,53.1413216224,1066.8 -1.9704573761,53.1402923625,1066.8 -1.9656763943,53.13959806939999,1066.8 -1.9607925076,53.1392484733,1066.8 -1.9558741591,53.1392484733,1066.8 -1.9509902724,53.13959806939999,1066.8 -1.9462092906,53.1402923625,1066.8 -1.9415982221,53.1413216224,1066.8 -1.9372217058,53.1426714238,1066.8 -1.9331411087,53.1443228474,1066.8 -1.9294136686,53.14625274370001,1066.8 -1.9260916927,53.14843405639999,1066.8 -1.9232218248,53.1508362003,1066.8 -1.9208443897,53.1534254881,1066.8 -1.9189928248,53.15616560210001,1066.8 -1.9176932075,53.15901810199999,1066.8 -1.9169638845,53.1619429631,1066.8 -1.916815208,53.1648991371,1066.8 -1.9172493842,53.1678451281,1066.8 -1.918260436,53.1707395745,1066.8 -1.9198342799,53.1735418303,1066.8 -1.9219489177,53.1762125364,1066.8 -1.9245747399,53.1787141743,1066.8 -1.9276749375,53.1810115942,1066.8 -1.9312060152,53.1830725106,1066.8 -1.935118401,53.1848679569,1066.8 -1.9393571422,53.1863726948,1066.8 -1.9438626785,53.1875655697,1066.8 -1.9485716812,53.1884298098,1066.8 -1.9534179472,53.1889532633,1066.8 -1.9583333333,53.1891285695,1066.8 + + + + +
+ + EGD305 BECKINGHAM + 530554N 0004134W -
530542N 0004034W -
530427N 0004044W -
530428N 0004205W -
530534N 0004217W -
530554N 0004134W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 07769-730481.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6927777778,53.0983333333,457.2 -0.7047222222,53.0927777778,457.2 -0.7013888889,53.0744444444,457.2 -0.6788888889,53.07416666669999,457.2 -0.6761111111,53.09499999999999,457.2 -0.6927777778,53.0983333333,457.2 + + + + +
+ + EGD307 DONNA NOOK + 532331N 0001354E -
532932N 0000503E thence clockwise by the arc of a circle radius 5 NM centred on 532830N 0001315E to -
532331N 0001354E
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 20,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / High Energy Manoeuvres / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUACS: Donna Nook Range on 122.750 MHz when open. SUAAIS: Donna Nook Range on 122.750 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01507-359126.

Remarks: Associated aircraft operations outside area boundary. 122.750 MHz is a common frequency also used by Holbeach and Pembrey AWRs. Ensure crossing clearance request is specific to Donna Nook AWR. SI 1939/451. UAS BVLOS will not be conducted above 12,000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2316666667,53.3919444444,7010.400000000001 0.2406825788,53.39252947290001,7010.400000000001 0.2496135246,53.3934738632,7010.400000000001 0.2584233162,53.3947627808,7010.400000000001 0.2670748532,53.3963907993,7010.400000000001 0.2755316902,53.398351064,7010.400000000001 0.283758188,53.4006353204,7010.400000000001 0.2917196616,53.4032339479,7010.400000000001 0.299382525,53.4061360005,7010.400000000001 0.3067144306,53.40932925129999,7010.400000000001 0.3136844052,53.4128002441,7010.400000000001 0.3202629797,53.41653434860001,7010.400000000001 0.3264223132,53.4205158216,7010.400000000001 0.3321363105,53.4247278727,7010.400000000001 0.3373807333,53.4291527337,7010.400000000001 0.3421333029,53.43377173329999,7010.400000000001 0.3463737964,53.4385653748,7010.400000000001 0.3500841336,53.4435134178,7010.400000000001 0.353248456,53.44859496269999,7010.400000000001 0.3558531958999999,53.45378853859999,7010.400000000001 0.3578871374000001,53.4590721933,7010.400000000001 0.3593414664,53.4644235858,7010.400000000001 0.3602098119,53.4698200802,7010.400000000001 0.3604882759999999,53.47523884140001,7010.400000000001 0.3601754547,53.4806569311,7010.400000000001 0.3592724472,53.4860514054,7010.400000000001 0.3577828553,53.4913994117,7010.400000000001 0.3557127719000001,53.4966782858,7010.400000000001 0.3530707586999999,53.501865648,7010.400000000001 0.3498678134,53.5069394986,7010.400000000001 0.3461173266,53.5118783116,7010.400000000001 0.3418350278,53.5166611264,7010.400000000001 0.3370389214,53.5212676377,7010.400000000001 0.3317492124,53.5256782822,7010.400000000001 0.3259882231,53.5298743225,7010.400000000001 0.3197802995,53.5338379274,7010.400000000001 0.313151709,53.5375522487,7010.400000000001 0.3061305297,53.5410014936,7010.400000000001 0.2987465312,53.54417099270001,7010.400000000001 0.2910310476,53.5470472631,7010.400000000001 0.2830168442,53.5496180668,7010.400000000001 0.2747379765,53.5518724632,7010.400000000001 0.2662296443,53.5538008569,7010.400000000001 0.2575280401,53.55539503859999,7010.400000000001 0.2486701928,53.556648221,7010.400000000001 0.2396938079,53.5575550683,7010.400000000001 0.2306371044,53.5581117187,7010.400000000001 0.2215386491,53.5583158018,7010.400000000001 0.2124371901,53.5581664484,7010.400000000001 0.2033714882,53.5576642946,7010.400000000001 0.1943801493,53.5568114788,7010.400000000001 0.1855014572,53.5556116326,7010.400000000001 0.1767732078,53.554069865,7010.400000000001 0.1682325452,53.5521927402,7010.400000000001 0.1599158018,53.54998824919999,7010.400000000001 0.1518583412,53.54746577560001,7010.400000000001 0.144094406,53.5446360542,7010.400000000001 0.1366569705,53.5415111256,7010.400000000001 0.1295775996,53.5381042833,7010.400000000001 0.1228863138,53.5344300172,7010.400000000001 0.116611461,53.5305039502,7010.400000000001 0.1107795966,53.52634277189999,7010.400000000001 0.1054153713,53.52196416590001,7010.400000000001 0.1005414271,53.51738673450001,7010.400000000001 0.0961783027,53.5126299184,7010.400000000001 0.09234434850000001,53.5077139136,7010.400000000001 0.08905565090000001,53.5026595851,7010.400000000001 0.0863259664,53.4974883771,7010.400000000001 0.0841666667,53.4922222222,7010.400000000001 0.2316666667,53.3919444444,7010.400000000001 + + + + +
+ + EGD314 HARPUR HILL + A circle, 0.5 NM radius, centred at 531343N 0015528W
Upper limit: 2900 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: Manchester APP on 118.580 MHz.

Contact: HSE (The Health and Safety Executive), Tel: 0203-028 2000.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9244444444,53.2369316665,883.9200000000001 -1.9272361795,53.2367613117,883.9200000000001 -1.9299135563,53.2362572255,883.9200000000001 -1.932366909,53.2354400564,883.9200000000001 -1.9344957623,53.2343432761,883.9200000000001 -1.9362129508,53.23301180599999,883.9200000000001 -1.9374481891,53.2315001758,883.9200000000001 -1.9381509465,53.2298702871,883.9200000000001 -1.9382925095,53.2281888772,883.9200000000001 -1.9378671475,53.2265247852,883.9200000000001 -1.9368923376,53.2249461335,883.9200000000001 -1.9354080383,53.2235175393,883.9200000000001 -1.9334750457,53.2222974722,883.9200000000001 -1.9311725002,53.2213358622,883.9200000000001 -1.9285946453,53.2206720594,883.9200000000001 -1.9258469737,53.2203332259,883.9200000000001 -1.9230419152,53.2203332259,883.9200000000001 -1.9202942436,53.2206720594,883.9200000000001 -1.9177163887,53.2213358622,883.9200000000001 -1.9154138432,53.2222974722,883.9200000000001 -1.9134808506,53.2235175393,883.9200000000001 -1.9119965513,53.2249461335,883.9200000000001 -1.9110217413,53.2265247852,883.9200000000001 -1.9105963794,53.2281888772,883.9200000000001 -1.9107379424,53.2298702871,883.9200000000001 -1.9114406998,53.2315001758,883.9200000000001 -1.9126759381,53.23301180599999,883.9200000000001 -1.9143931266,53.2343432761,883.9200000000001 -1.9165219799,53.2354400564,883.9200000000001 -1.9189753326,53.2362572255,883.9200000000001 -1.9216527094,53.2367613117,883.9200000000001 -1.9244444444,53.2369316665,883.9200000000001 + + + + +
+ + EGD323A SOUTHERN COMPLEX + 551710N 0001428E -
550143N 0011753E -
543102N 0003132W -
544841N 0005456W -
545744N 0005457W -
551710N 0001428E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,1524 -0.9158333333000001,54.96233333329999,1524 -0.9156,54.8112972222,1524 -0.5256138889,54.5171138889,1524 1.298075,55.0285222222,1524 0.2412277778,55.2861722222,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,1524 -0.9158333333000001,54.96233333329999,1524 -0.9158333333000001,54.96233333329999,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,1524 -0.9156,54.8112972222,1524 -0.9156,54.8112972222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9158333333000001,54.96233333329999,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,1524 -0.5256138889,54.5171138889,1524 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,1524 1.298075,55.0285222222,1524 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 0.2412277778,55.2861722222,1524 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524 + + + + + +
+ + EGD323B SOUTHERN COMPLEX + 550143N 0011753E -
545059N 0020010E -
541451N 0001028W -
543102N 0003132W -
550143N 0011753E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 -0.5256138889,54.5171138889,1524 -0.1744611111,54.24745,1524 2.0026916667,54.8496888889,1524 1.298075,55.0285222222,1524 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,1524 -0.5256138889,54.5171138889,1524 -0.5256138889,54.5171138889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,1524 -0.1744611111,54.24745,1524 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,1524 2.0026916667,54.8496888889,1524 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 1.298075,55.0285222222,1524 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524 + + + + + +
+ + EGD323C SOUTHERN COMPLEX + 545059N 0020010E -
544532N 0022109E -
540644N 0000002W -
541451N 0001028W -
545059N 0020010E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,20116.8 -0.1744611111,54.24745,20116.8 -0.0005361111,54.11218055559999,20116.8 2.3526361111,54.75875000000001,20116.8 2.0026916667,54.8496888889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 -0.1744611111,54.24745,1524 -0.0005361111,54.11218055559999,1524 2.3526361111,54.75875000000001,1524 2.0026916667,54.8496888889,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,1524 -0.1744611111,54.24745,1524 -0.1744611111,54.24745,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,1524 -0.0005361111,54.11218055559999,1524 -0.0005361111,54.11218055559999,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,1524 2.3526361111,54.75875000000001,1524 2.3526361111,54.75875000000001,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 2.0026916667,54.8496888889,1524 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,1524 + + + + + +
+ + EGD323D SOUTHERN COMPLEX + 544532N 0022109E -
543948N 0024252E -
543143N 0025434E -
541738N 0030110E -
533813N 0003557E -
540644N 0000002W -
544532N 0022109E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,20116.8 -0.0005361111,54.11218055559999,20116.8 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875000000001,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 -0.0005361111,54.11218055559999,1524 0.599175,53.6369388889,1524 3.0193416667,54.2940166667,1524 2.9095444444,54.5285361111,1524 2.7144361111,54.6632333333,1524 2.3526361111,54.75875000000001,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,1524 -0.0005361111,54.11218055559999,1524 -0.0005361111,54.11218055559999,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,1524 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,1524 0.599175,53.6369388889,1524 0.599175,53.6369388889,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,1524 3.0193416667,54.2940166667,1524 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 2.9095444444,54.5285361111,1524 2.9095444444,54.5285361111,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.9095444444,54.5285361111,1524 2.7144361111,54.6632333333,1524 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.7144361111,54.6632333333,1524 2.3526361111,54.75875000000001,1524 2.3526361111,54.75875000000001,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,1524 + + + + + +
+ + EGD323E SOUTHERN COMPLEX + 541738N 0030110E -
541733N 0030112E -
535535N 0025714E -
532807N 0024241E -
533813N 0003557E -
541738N 0030110E
Upper limit: FL660
Lower limit: FL50
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,20116.8 0.599175,53.6369388889,20116.8 2.7113888889,53.4686111111,20116.8 2.9538888889,53.92638888889999,20116.8 3.0200138889,54.29257222219999,20116.8 3.0193416667,54.2940166667,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 0.599175,53.6369388889,1524 2.7113888889,53.4686111111,1524 2.9538888889,53.92638888889999,1524 3.0200138889,54.29257222219999,1524 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0193416667,54.2940166667,1524 0.599175,53.6369388889,1524 0.599175,53.6369388889,20116.8 3.0193416667,54.2940166667,20116.8 3.0193416667,54.2940166667,1524 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,1524 2.7113888889,53.4686111111,1524 2.7113888889,53.4686111111,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.7113888889,53.4686111111,1524 2.9538888889,53.92638888889999,1524 2.9538888889,53.92638888889999,20116.8 2.7113888889,53.4686111111,20116.8 2.7113888889,53.4686111111,1524 + + + + + + relativeToGround + + + relativeToGround + + 2.9538888889,53.92638888889999,1524 3.0200138889,54.29257222219999,1524 3.0200138889,54.29257222219999,20116.8 2.9538888889,53.92638888889999,20116.8 2.9538888889,53.92638888889999,1524 + + + + + + relativeToGround + + + relativeToGround + + 3.0200138889,54.29257222219999,1524 3.0193416667,54.2940166667,1524 3.0193416667,54.2940166667,20116.8 3.0200138889,54.29257222219999,20116.8 3.0200138889,54.29257222219999,1524 + + + + + +
+ + EGD323F SOUTHERN COMPLEX + 545744N 0005457W -
544841N 0005456W -
542402N 0005518W -
544229N 0011251W -
545210N 0010815W -
545513N 0010343W -
545744N 0005457W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,20116.8 -1.0619444444,54.9202777778,20116.8 -1.1375,54.8694444444,20116.8 -1.2140305556,54.7081583333,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9156,54.8112972222,20116.8 -0.9158333333000001,54.96233333329999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,4572 -1.0619444444,54.9202777778,4572 -1.1375,54.8694444444,4572 -1.2140305556,54.7081583333,4572 -0.9216388889,54.40066111109999,4572 -0.9156,54.8112972222,4572 -0.9158333333000001,54.96233333329999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9158333333000001,54.96233333329999,4572 -1.0619444444,54.9202777778,4572 -1.0619444444,54.9202777778,20116.8 -0.9158333333000001,54.96233333329999,20116.8 -0.9158333333000001,54.96233333329999,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.0619444444,54.9202777778,4572 -1.1375,54.8694444444,4572 -1.1375,54.8694444444,20116.8 -1.0619444444,54.9202777778,20116.8 -1.0619444444,54.9202777778,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.1375,54.8694444444,4572 -1.2140305556,54.7081583333,4572 -1.2140305556,54.7081583333,20116.8 -1.1375,54.8694444444,20116.8 -1.1375,54.8694444444,4572 + + + + + + relativeToGround + + + relativeToGround + + -1.2140305556,54.7081583333,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -1.2140305556,54.7081583333,20116.8 -1.2140305556,54.7081583333,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.9156,54.8112972222,4572 -0.9156,54.8112972222,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9158333333000001,54.96233333329999,4572 -0.9158333333000001,54.96233333329999,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572 + + + + + +
+ + EGD323G SOUTHERN COMPLEX + 544841N 0005456W -
543102N 0003132W -
542402N 0005518W -
544841N 0005456W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.5256138889,54.5171138889,20116.8 -0.9156,54.8112972222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9216388889,54.40066111109999,4572 -0.5256138889,54.5171138889,4572 -0.9156,54.8112972222,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9156,54.8112972222,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -0.9156,54.8112972222,20116.8 -0.9156,54.8112972222,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.5256138889,54.5171138889,4572 -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9156,54.8112972222,4572 -0.9156,54.8112972222,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572 + + + + + +
+ + EGD323H SOUTHERN COMPLEX + 543102N 0003132W -
541451N 0001028W -
540726N 0003547W -
542402N 0005518W -
543102N 0003132W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.5256138889,54.5171138889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9216388889,54.40066111109999,4572 -0.5964777778,54.1240138889,4572 -0.1744611111,54.24745,4572 -0.5256138889,54.5171138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5256138889,54.5171138889,4572 -0.9216388889,54.40066111109999,4572 -0.9216388889,54.40066111109999,20116.8 -0.5256138889,54.5171138889,20116.8 -0.5256138889,54.5171138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.9216388889,54.40066111109999,4572 -0.5964777778,54.1240138889,4572 -0.5964777778,54.1240138889,20116.8 -0.9216388889,54.40066111109999,20116.8 -0.9216388889,54.40066111109999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5964777778,54.1240138889,4572 -0.1744611111,54.24745,4572 -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5256138889,54.5171138889,4572 -0.5256138889,54.5171138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572 + + + + + +
+ + EGD323J SOUTHERN COMPLEX + 541451N 0001028W -
540644N 0000002W -
535908N 0002606W -
540726N 0003547W -
541451N 0001028W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,20116.8 -0.5964777778,54.1240138889,20116.8 -0.4349,53.9855666667,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.1744611111,54.24745,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5964777778,54.1240138889,4572 -0.4349,53.9855666667,4572 -0.0005361111,54.11218055559999,4572 -0.1744611111,54.24745,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1744611111,54.24745,4572 -0.5964777778,54.1240138889,4572 -0.5964777778,54.1240138889,20116.8 -0.1744611111,54.24745,20116.8 -0.1744611111,54.24745,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.5964777778,54.1240138889,4572 -0.4349,53.9855666667,4572 -0.4349,53.9855666667,20116.8 -0.5964777778,54.1240138889,20116.8 -0.5964777778,54.1240138889,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.4349,53.9855666667,4572 -0.0005361111,54.11218055559999,4572 -0.0005361111,54.11218055559999,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.1744611111,54.24745,4572 -0.1744611111,54.24745,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,4572 + + + + + +
+ + EGD323K SOUTHERN COMPLEX + 540644N 0000002W -
533813N 0003557E -
534331N 0000805W -
535908N 0002606W -
540644N 0000002W
Upper limit: FL660
Lower limit: FL150
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,20116.8 -0.4349,53.9855666667,20116.8 -0.1348055556,53.7253805556,20116.8 0.599175,53.6369388889,20116.8 -0.0005361111,54.11218055559999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.4349,53.9855666667,4572 -0.1348055556,53.7253805556,4572 0.599175,53.6369388889,4572 -0.0005361111,54.11218055559999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.0005361111,54.11218055559999,4572 -0.4349,53.9855666667,4572 -0.4349,53.9855666667,20116.8 -0.0005361111,54.11218055559999,20116.8 -0.0005361111,54.11218055559999,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.4349,53.9855666667,4572 -0.1348055556,53.7253805556,4572 -0.1348055556,53.7253805556,20116.8 -0.4349,53.9855666667,20116.8 -0.4349,53.9855666667,4572 + + + + + + relativeToGround + + + relativeToGround + + -0.1348055556,53.7253805556,4572 0.599175,53.6369388889,4572 0.599175,53.6369388889,20116.8 -0.1348055556,53.7253805556,20116.8 -0.1348055556,53.7253805556,4572 + + + + + + relativeToGround + + + relativeToGround + + 0.599175,53.6369388889,4572 -0.0005361111,54.11218055559999,4572 -0.0005361111,54.11218055559999,20116.8 0.599175,53.6369388889,20116.8 0.599175,53.6369388889,4572 + + + + + +
+ + EGD323L SOUTHERN COMPLEX + 552430N 0004952E -
550944N 0014759E -
550143N 0011753E -
551710N 0001428E -
552430N 0004952E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,20116.8 0.2412277778,55.2861722222,20116.8 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 0.2412277778,55.2861722222,3048 1.298075,55.0285222222,3048 1.7996194444,55.1621805556,3048 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 0.2412277778,55.2861722222,3048 0.2412277778,55.2861722222,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.2412277778,55.2861722222,3048 1.298075,55.0285222222,3048 1.298075,55.0285222222,20116.8 0.2412277778,55.2861722222,20116.8 0.2412277778,55.2861722222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 0.8311305556,55.4081972222,3048 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + +
+ + EGD323M SOUTHERN COMPLEX + 550944N 0014759E -
545840N 0022938E -
545059N 0020010E -
550143N 0011753E -
550944N 0014759E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,20116.8 1.298075,55.0285222222,20116.8 2.0026916667,54.8496888889,20116.8 2.4938992222,54.97779488889999,20116.8 1.7996194444,55.1621805556,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 1.298075,55.0285222222,3048 2.0026916667,54.8496888889,3048 2.4938992222,54.97779488889999,3048 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 1.298075,55.0285222222,3048 1.298075,55.0285222222,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.298075,55.0285222222,3048 2.0026916667,54.8496888889,3048 2.0026916667,54.8496888889,20116.8 1.298075,55.0285222222,20116.8 1.298075,55.0285222222,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + +
+ + EGD323N SOUTHERN COMPLEX + 545840N 0022938E -
544951N 0023752E -
544532N 0022109E -
545059N 0020010E -
545840N 0022938E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,20116.8 2.0026916667,54.8496888889,20116.8 2.3526361111,54.75875000000001,20116.8 2.6309753889,54.8308915833,20116.8 2.4938992222,54.97779488889999,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.0026916667,54.8496888889,3048 2.3526361111,54.75875000000001,3048 2.6309753889,54.8308915833,3048 2.4938992222,54.97779488889999,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.0026916667,54.8496888889,3048 2.0026916667,54.8496888889,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.0026916667,54.8496888889,3048 2.3526361111,54.75875000000001,3048 2.3526361111,54.75875000000001,20116.8 2.0026916667,54.8496888889,20116.8 2.0026916667,54.8496888889,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,3048 2.6309753889,54.8308915833,3048 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048 + + + + + +
+ + EGD323P SOUTHERN COMPLEX + 544951N 0023752E -
543143N 0025434E -
543948N 0024252E -
544532N 0022109E -
544951N 0023752E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,20116.8 2.3526361111,54.75875000000001,20116.8 2.7144361111,54.6632333333,20116.8 2.9095444444,54.5285361111,20116.8 2.6309753889,54.8308915833,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.3526361111,54.75875000000001,3048 2.7144361111,54.6632333333,3048 2.9095444444,54.5285361111,3048 2.6309753889,54.8308915833,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.6309753889,54.8308915833,3048 2.3526361111,54.75875000000001,3048 2.3526361111,54.75875000000001,20116.8 2.6309753889,54.8308915833,20116.8 2.6309753889,54.8308915833,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.3526361111,54.75875000000001,3048 2.7144361111,54.6632333333,3048 2.7144361111,54.6632333333,20116.8 2.3526361111,54.75875000000001,20116.8 2.3526361111,54.75875000000001,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.7144361111,54.6632333333,3048 2.9095444444,54.5285361111,3048 2.9095444444,54.5285361111,20116.8 2.7144361111,54.6632333333,20116.8 2.7144361111,54.6632333333,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.9095444444,54.5285361111,3048 2.6309753889,54.8308915833,3048 2.6309753889,54.8308915833,20116.8 2.9095444444,54.5285361111,20116.8 2.9095444444,54.5285361111,3048 + + + + + +
+ + EGD323Q SOUTHERN COMPLEX + 553347N 0013625E -
553150N 0015622E -
551616N 0021300E -
550944N 0014759E -
552430N 0004952E -
553347N 0013625E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,20116.8 0.8311305556,55.4081972222,20116.8 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 1.9394305556,55.5305138889,20116.8 1.6068611111,55.5631527778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,3048 0.8311305556,55.4081972222,3048 1.7996194444,55.1621805556,3048 2.2167416667,55.2711027778,3048 1.9394305556,55.5305138889,3048 1.6068611111,55.5631527778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.6068611111,55.5631527778,3048 0.8311305556,55.4081972222,3048 0.8311305556,55.4081972222,20116.8 1.6068611111,55.5631527778,20116.8 1.6068611111,55.5631527778,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8311305556,55.4081972222,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 0.8311305556,55.4081972222,20116.8 0.8311305556,55.4081972222,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 2.2167416667,55.2711027778,3048 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.9394305556,55.5305138889,3048 1.9394305556,55.5305138889,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.9394305556,55.5305138889,3048 1.6068611111,55.5631527778,3048 1.6068611111,55.5631527778,20116.8 1.9394305556,55.5305138889,20116.8 1.9394305556,55.5305138889,3048 + + + + + +
+ + EGD323R SOUTHERN COMPLEX + 551616N 0021300E -
545840N 0022938E -
550944N 0014759E -
551616N 0021300E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards / Unmanned Aircraft System (BVLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,20116.8 1.7996194444,55.1621805556,20116.8 2.4938992222,54.97779488889999,20116.8 2.2167416667,55.2711027778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.7996194444,55.1621805556,3048 2.4938992222,54.97779488889999,3048 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.2167416667,55.2711027778,3048 1.7996194444,55.1621805556,3048 1.7996194444,55.1621805556,20116.8 2.2167416667,55.2711027778,20116.8 2.2167416667,55.2711027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.7996194444,55.1621805556,3048 2.4938992222,54.97779488889999,3048 2.4938992222,54.97779488889999,20116.8 1.7996194444,55.1621805556,20116.8 1.7996194444,55.1621805556,3048 + + + + + + relativeToGround + + + relativeToGround + + 2.4938992222,54.97779488889999,3048 2.2167416667,55.2711027778,3048 2.2167416667,55.2711027778,20116.8 2.4938992222,54.97779488889999,20116.8 2.4938992222,54.97779488889999,3048 + + + + + +
+ + EGD324A WADDINGTON LOW + A circle, 5 NM radius, centred at 530958N 0003126W
Upper limit: FL105
Lower limit: SFC
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.

Contact: Waddington ATC, Tel: 01522-727451/727452.

Remarks: High energy manoeuvres related to display flying training only.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5238888889,53.24931701730001,3200.4 -0.5329620222,53.2491385233,3200.4 -0.5419960775,53.24860381020001,3200.4 -0.5509521479,53.24771518070001,3200.4 -0.5597916681,53.2464764618,3200.4 -0.5684765836,53.24489298790001,3200.4 -0.5769695164,53.2429715769,3200.4 -0.5852339289,53.2407205011,3200.4 -0.5932342833000001,53.23814945079999,3200.4 -0.6009361957,53.2352694915,3200.4 -0.6083065862,53.2320930161,3200.4 -0.6153138218,53.2286336905,3200.4 -0.6219278531,53.2249063941,3200.4 -0.6281203442,53.2209271548,3200.4 -0.6338647934,53.21671307940001,3200.4 -0.6391366472,53.2122822792,3200.4 -0.6439134041,53.2076537911,3200.4 -0.6481747101000001,53.20284749500001,3200.4 -0.6519024438,53.197884028,3200.4 -0.6550807917,53.19278469469999,3200.4 -0.6576963139000001,53.1875713753,3200.4 -0.6597379981,53.18226643100001,3200.4 -0.6611973038,53.1768926078,3200.4 -0.6620681955,53.17147293869999,3200.4 -0.6623471645,53.1660306441,3200.4 -0.6620332407,53.1605890328,3200.4 -0.6611279923,53.1551714022,3200.4 -0.6596355158,53.1498009378,3200.4 -0.6575624144,53.144500615,3200.4 -0.6549177658999999,53.1392931008,3200.4 -0.651713081,53.13420065700001,3200.4 -0.6479622505,53.129245046,3200.4 -0.6436814828,53.124447438,3200.4 -0.6388892324,53.1198283214,3200.4 -0.6336061185,53.11540741570001,3200.4 -0.6278548351,53.1112035887,3200.4 -0.6216600529,53.10723477610001,3200.4 -0.6150483124,53.1035179065,3200.4 -0.6080479107,53.1000688292,3200.4 -0.6006887801,53.09690224840001,3200.4 -0.5930023609,53.0940316606,3200.4 -0.5850214681,53.0914692984,3200.4 -0.5767801523,53.0892260788,3200.4 -0.5683135565,53.0873115574,3200.4 -0.5596577674,53.0857338887,3200.4 -0.5508496647,53.0844997914,3200.4 -0.5419267654,53.0836145207,3200.4 -0.5329270671,53.0830818461,3200.4 -0.5238888889,53.0829040355,3200.4 -0.5148507107,53.0830818461,3200.4 -0.5058510124,53.0836145207,3200.4 -0.4969281131,53.0844997914,3200.4 -0.4881200103,53.0857338887,3200.4 -0.4794642213,53.0873115574,3200.4 -0.4709976254000001,53.0892260788,3200.4 -0.4627563097,53.0914692984,3200.4 -0.4547754169,53.0940316606,3200.4 -0.4470889977,53.09690224840001,3200.4 -0.4397298670999999,53.1000688292,3200.4 -0.4327294654,53.1035179065,3200.4 -0.4261177249,53.10723477610001,3200.4 -0.4199229426,53.1112035887,3200.4 -0.4141716593,53.11540741570001,3200.4 -0.4088885453,53.1198283214,3200.4 -0.4040962949,53.124447438,3200.4 -0.3998155273,53.129245046,3200.4 -0.3960646967,53.13420065700001,3200.4 -0.3928600119,53.1392931008,3200.4 -0.3902153634000001,53.144500615,3200.4 -0.3881422619,53.1498009378,3200.4 -0.3866497854,53.1551714022,3200.4 -0.3857445371,53.1605890328,3200.4 -0.3854306133000001,53.1660306441,3200.4 -0.3857095823,53.17147293869999,3200.4 -0.386580474,53.1768926078,3200.4 -0.3880397797,53.18226643100001,3200.4 -0.3900814637999999,53.1875713753,3200.4 -0.3926969860000001,53.19278469469999,3200.4 -0.395875334,53.197884028,3200.4 -0.3996030676,53.20284749500001,3200.4 -0.4038643737,53.2076537911,3200.4 -0.4086411306,53.2122822792,3200.4 -0.4139129844,53.21671307940001,3200.4 -0.4196574336,53.2209271548,3200.4 -0.4258499247,53.2249063941,3200.4 -0.432463956,53.2286336905,3200.4 -0.4394711915999999,53.2320930161,3200.4 -0.4468415821,53.2352694915,3200.4 -0.4545434945,53.23814945079999,3200.4 -0.4625438488,53.2407205011,3200.4 -0.4708082614,53.2429715769,3200.4 -0.4793011942,53.24489298790001,3200.4 -0.4879861096000001,53.2464764618,3200.4 -0.4968256299,53.24771518070001,3200.4 -0.5057817003,53.24860381020001,3200.4 -0.5148157555,53.2491385233,3200.4 -0.5238888889,53.24931701730001,3200.4 + + + + +
+ + EGD324B WADDINGTON MEDIUM + 531343N 0004324W -
530818N 0001452W -
525556N 0002123W -
530120N 0004950W -
531343N 0004324W
Upper limit: FL195
Lower limit: FL105
Class: Activity: Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Waddington ATC on 119.500 MHz. SUAAIS: London Information on 124.600 MHz.

Contact: Waddington ATC, Tel: 01522-727451/727452.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,5943.6 -0.8306333333000001,53.0220944444,5943.6 -0.3564722222,52.93216944440001,5943.6 -0.247825,53.1383611111,5943.6 -0.7233333333,53.2286111111,5943.6 + + + + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,3200.4 -0.8306333333000001,53.0220944444,3200.4 -0.3564722222,52.93216944440001,3200.4 -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.7233333333,53.2286111111,3200.4 -0.8306333333000001,53.0220944444,3200.4 -0.8306333333000001,53.0220944444,5943.6 -0.7233333333,53.2286111111,5943.6 -0.7233333333,53.2286111111,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.8306333333000001,53.0220944444,3200.4 -0.3564722222,52.93216944440001,3200.4 -0.3564722222,52.93216944440001,5943.6 -0.8306333333000001,53.0220944444,5943.6 -0.8306333333000001,53.0220944444,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.3564722222,52.93216944440001,3200.4 -0.247825,53.1383611111,3200.4 -0.247825,53.1383611111,5943.6 -0.3564722222,52.93216944440001,5943.6 -0.3564722222,52.93216944440001,3200.4 + + + + + + relativeToGround + + + relativeToGround + + -0.247825,53.1383611111,3200.4 -0.7233333333,53.2286111111,3200.4 -0.7233333333,53.2286111111,5943.6 -0.247825,53.1383611111,5943.6 -0.247825,53.1383611111,3200.4 + + + + + +
+ + EGD401 BALLYKINLER + 541334N 0054612W -
541256N 0054734W -
541316N 0055038W -
541440N 0054940W - then along the river to
541526N 0055010W -
541525N 0054718W -
541334N 0054612W
Upper limit: 3200 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 02844-610392.

Remarks: SI 1940/756.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.77,54.2261111111,975.36 -5.7883333333,54.25694444440001,975.36 -5.8361111111,54.25722222219999,975.36 -5.835386111100001,54.2552055556,975.36 -5.828741666699999,54.2502138889,975.36 -5.8250583333,54.2466888889,975.36 -5.825505555600001,54.2453583333,975.36 -5.8277777778,54.2444444444,975.36 -5.8438888889,54.2211111111,975.36 -5.7927777778,54.2155555556,975.36 -5.77,54.2261111111,975.36 + + + + +
+ + EGD402A LUCE BAY (N) + 550332N 0050509W -
545600N 0045800W -
545600N 0044744W -
544650N 0043837W -
545008N 0044939W -
545100N 0044946W -
545217N 0045134W -
545208N 0045404W -
544953N 0045653W -
544541N 0045627W -
544215N 0045339W -
544007N 0045032W -
543915N 0044653W -
543815N 0045352W -
545812N 0051210W -
550218N 0050909W -
550332N 0050509W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0858333333,55.0588888889,7010.400000000001 -5.1525,55.0383333333,7010.400000000001 -5.2027777778,54.97,7010.400000000001 -4.8977777778,54.63750000000001,7010.400000000001 -4.7813888889,54.6541666667,7010.400000000001 -4.8422222222,54.6686111111,7010.400000000001 -4.8941666667,54.7041666667,7010.400000000001 -4.9408333333,54.7613888889,7010.400000000001 -4.9480555556,54.8313888889,7010.400000000001 -4.9011111111,54.8688888889,7010.400000000001 -4.8594444444,54.8713888889,7010.400000000001 -4.8294444444,54.85,7010.400000000001 -4.8275,54.83555555560001,7010.400000000001 -4.6436111111,54.7805555556,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + +
+ + EGD402B LUCE BAY (N) + 550332N 0050509W -
550254N 0045410W -
545600N 0044744W -
545600N 0045800W -
550332N 0050509W
Upper limit: 23000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 23,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0858333333,55.0588888889,7010.400000000001 -4.9666666667,54.9333333333,7010.400000000001 -4.7955555556,54.9333333333,7010.400000000001 -4.9027777778,55.0483333333,7010.400000000001 -5.0858333333,55.0588888889,7010.400000000001 + + + + +
+ + EGD402C LUCE BAY (N) + A circle, 3000 FT radius, centred at 545659N 0045752W
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9644444444,54.9579361819,1219.2 -4.9673177437,54.9577680078,1219.2 -4.9700733403,54.9572703748,1219.2 -4.9725983613,54.9564636675,1219.2 -4.9747893947,54.9553809299,1219.2 -4.9765567285,54.9540665095,1219.2 -4.9778280257,54.9525742383,1219.2 -4.9785512828,54.95096522630001,1219.2 -4.9786969516,54.9493053564,1219.2 -4.9782591389,54.94766258589999,1219.2 -4.9772558366,54.9461041639,1219.2 -4.9757281738,54.9446938793,1219.2 -4.9737387244,54.9434894509,1219.2 -4.9713689403,54.942540168,1219.2 -4.968715816,54.9418848754,1219.2 -4.9658879218,54.94155038609999,1219.2 -4.963000967,54.94155038609999,1219.2 -4.9601730729,54.9418848754,1219.2 -4.9575199486,54.942540168,1219.2 -4.9551501645,54.9434894509,1219.2 -4.9531607151,54.9446938793,1219.2 -4.9516330523,54.9461041639,1219.2 -4.95062975,54.94766258589999,1219.2 -4.9501919373,54.9493053564,1219.2 -4.9503376061,54.95096522630001,1219.2 -4.9510608631,54.9525742383,1219.2 -4.9523321604,54.9540665095,1219.2 -4.9540994942,54.9553809299,1219.2 -4.9562905276,54.9564636675,1219.2 -4.9588155486,54.9572703748,1219.2 -4.9615711452,54.9577680078,1219.2 -4.9644444444,54.9579361819,1219.2 + + + + +
+ + EGD403A LUCE BAY + 545141N 0045438W -
545139N 0045041W -
545100N 0044946W -
544850N 0045646W -
544953N 0045653W -
545141N 0045438W
Upper limit: 3000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9105555556,54.8613888889,914.4000000000001 -4.9480555556,54.8313888889,914.4000000000001 -4.9461111111,54.8138888889,914.4000000000001 -4.8294444444,54.85,914.4000000000001 -4.8447222222,54.8608333333,914.4000000000001 -4.9105555556,54.8613888889,914.4000000000001 + + + + +
+ + EGD403B LUCE BAY + 545208N 0045404W -
545217N 0045134W -
545100N 0044946W -
545008N 0044939W -
544650N 0043837W -
544304N 0043500W -
544050N 0043543W -
543915N 0044653W -
544007N 0045032W -
544215N 0045339W -
544541N 0045627W -
544953N 0045653W -
545208N 0045404W
Upper limit: 35000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Luce Bay Information on 130.050 MHz or Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Control, Tel: 01776-888930.

Remarks: On no account should negative contact on 130.050 MHz be taken as non-activity of the range. SI 1940/1819.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9011111111,54.8688888889,10668 -4.9480555556,54.8313888889,10668 -4.9408333333,54.7613888889,10668 -4.8941666667,54.7041666667,10668 -4.8422222222,54.6686111111,10668 -4.7813888889,54.6541666667,10668 -4.5952777778,54.6805555556,10668 -4.5833333333,54.7177777778,10668 -4.6436111111,54.7805555556,10668 -4.8275,54.83555555560001,10668 -4.8294444444,54.85,10668 -4.8594444444,54.8713888889,10668 -4.9011111111,54.8688888889,10668 + + + + +
+ + EGD405 KIRKCUDBRIGHT + 544647N 0040349W -
544744N 0040214W -
544828N 0040040W -
544818N 0035705W -
544710N 0035630W -
543800N 0034806W -
543302N 0035720W -
543315N 0041341W -
543537N 0041514W -
544647N 0040349W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 15,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 50,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Kirkcudbright Range TSO, Tel: 01412-248500. DTSO 01412-248501.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0636111111,54.7797222222,15240 -4.2538888889,54.5936111111,15240 -4.2280555556,54.5541666667,15240 -3.9555555556,54.5505555556,15240 -3.8016666667,54.6333333333,15240 -3.9416666667,54.7861111111,15240 -3.9513888889,54.80499999999999,15240 -4.0111111111,54.80777777779999,15240 -4.0372222222,54.7955555556,15240 -4.0636111111,54.7797222222,15240 + + + + +
+ + EGD406A ESKMEALS + 542057N 0032747W thence clockwise by the arc of a circle radius 2 NM centred on 541900N 0032705W to
541701N 0032723W -
540634N 0033920W thence clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to
542357N 0034917W -
542846N 0033842W -
542057N 0032747W
Upper limit: 80000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 50,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Remarks: Aircraft following the west coast may proceed through the Danger Area at a height not below 2000 FT but it is essential that they remain east of the main railway line paralleling the coast while within the Danger Area. SI 1982/1180.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4630555556,54.3491666667,24384 -3.645,54.4794444444,24384 -3.821388888900001,54.3991666667,24384 -3.8264346983,54.3902456908,24384 -3.8308435947,54.381210064,24384 -3.8346650828,54.3720838636,24384 -3.8378941188,54.3628800713,24384 -3.8405265112,54.353611771,24384 -3.8425589244,54.3442921289,24384 -3.8439888809,54.3349343758,24384 -3.8448147631,54.3255517871,24384 -3.8450358126,54.3161576648,24384 -3.8446521295,54.306765318,24384 -3.8436646694,54.29738804439999,24384 -3.8420752404,54.2880391114,24384 -3.839886497400001,54.2787317371,24384 -3.8371019368,54.2694790723,24384 -3.8337258888,54.26029418169999,24384 -3.8297635095,54.2511900257,24384 -3.8252207712,54.24217944219999,24384 -3.8201044522,54.233275129,24384 -3.814422124900001,54.2244896262,24384 -3.8081821439,54.2158352985,24384 -3.801393632,54.2073243185,24384 -3.794066465599999,54.19896864990001,24384 -3.7862112598,54.19078003090001,24384 -3.7778393517,54.1827699581,24384 -3.7689627833,54.1749496712,24384 -3.7595942835,54.1673301372,24384 -3.7497472491,54.1599220357,24384 -3.7394357252,54.1527357444,24384 -3.7286743851,54.14578132510001,24384 -3.7174785086,54.1390685101,24384 -3.7058639609,54.1326066888,24384 -3.693847169300001,54.1264048954,24384 -3.6814451008,54.12047179679999,24384 -3.6686752382,54.1148156806,24384 -3.6555555556,54.1094444444,24384 -3.4563888889,54.2836111111,24384 -3.4506623994,54.2834617223,24384 -3.4449398451,54.2836739162,24384 -3.4392829629,54.28422262110001,24384 -3.433749363,54.28510224950001,24384 -3.428395409000001,54.2863038428,24384 -3.4232756474,54.2878151632,24384 -3.4184422552,54.2896208163,24384 -3.4139445105,54.291702408,24384 -3.409828292199999,54.2940387298,24384 -3.4061356127,54.2966059743,24384 -3.4029041892,54.2993779763,24384 -3.4001670583,54.3023264784,24384 -3.397952236,54.3054214177,24384 -3.396282429,54.3086312313,24384 -3.3951747988,54.3119231776,24384 -3.3946407821,54.3152636691,24384 -3.3946859681,54.318618615,24384 -3.3953100364,54.3219537687,24384 -3.396506754399999,54.3252350775,24384 -3.3982640352,54.32842903030001,24384 -3.4005640558,54.3315030008,24384 -3.4033834341,54.334425581,24384 -3.4066934642,54.3371669033,24384 -3.410460405999999,54.339698947,24384 -3.4146458278,54.3419958252,24384 -3.4192069976,54.34403405159999,24384 -3.4240973199,54.3457927812,24384 -3.429266812799999,54.3472540251,24384 -3.434662620600001,54.3484028352,24384 -3.4402295569,54.3492274587,24384 -3.4459106726,54.3497194586,24384 -3.4516478419,54.3498738009,24384 -3.4573823616,54.3496889063,24384 -3.4630555556,54.3491666667,24384 + + + + +
+ + EGD406B ESKMEALS + 541913N 0035042W thence anti-clockwise by the arc of a circle radius 15 NM centred on 541900N 0032505W to
541049N 0034630W -
540804N 0035336W thence clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to
541916N 0035914W -
541913N 0035042W
Upper limit: 80000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 50,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 80,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.845,54.3202777778,24384 -3.9872222222,54.3211111111,24384 -3.9871594946,54.3107175685,24384 -3.9864927438,54.3003308501,24384 -3.985272219,54.2899613462,24384 -3.9834995252,54.2796191549,24384 -3.9811768014,54.26931434,24384 -3.9783067165,54.2590569217,24384 -3.9748924651,54.2488568664,24384 -3.970937763199999,54.23872407790001,24384 -3.9664468432,54.2286683871,24384 -3.9614244476,54.21869954340001,24384 -3.955875824,54.2088272049,24384 -3.9498067176,54.1990609292,24384 -3.9432233654,54.189410165,24384 -3.936132488,54.1798842425,24384 -3.9285412827,54.17049236490001,24384 -3.9204574148,54.1612435998,24384 -3.9118890095,54.15214687069999,24384 -3.902844642999999,54.1432109488,24384 -3.8933333333,54.1344444444,24384 -3.775,54.1802777778,24384 -3.7834591208,54.18808690669999,24384 -3.7913702592,54.1960923758,24384 -3.7987730162,54.2042637884,24384 -3.8056570042,54.2125900125,24384 -3.8120125251,54.2210596989,24384 -3.8178305841,54.2296612956,24384 -3.8231029043,54.2383830637,24384 -3.827821939,54.24721309289999,24384 -3.831980884,54.25613931740001,24384 -3.8355736883,54.2651495321,24384 -3.838595064899999,54.27423140929999,24384 -3.8410404991,54.2833725151,24384 -3.8429062576,54.2925603262,24384 -3.8441893949,54.30178224709999,24384 -3.8448877597,54.3110256271,24384 -3.845,54.3202777778,24384 + + + + +
+ + EGD406C ESKMEALS + 541916N 0035914W thence anti-clockwise by the arc of a circle radius 20 NM centred on 541900N 0032505W to
540804N 0035336W -
541027N 0040844W thence clockwise by the arc of a circle radius 27 NM centred on 541900N 0032505W to
541413N 0041025W -
541916N 0035914W
Upper limit: 50000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Eskmeals Information on 122.750 MHz or London Information on 125.475 MHz.

Contact: Pre-flight information: Eskmeals Range, Tel: 01229-712245/712233.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9872222222,54.3211111111,15240 -4.1736111111,54.2369444444,15240 -4.1699727629,54.2263311513,15240 -4.1659452033,54.2157666889,15240 -4.1614866885,54.20526197990001,15240 -4.1566001131,54.1948230752,15240 -4.1512886114,54.1844559832,15240 -4.1455555556,54.1741666667,15240 -3.8933333333,54.1344444444,15240 -3.902802936100001,54.1432260183,15240 -3.9118465154,54.1521611714,15240 -3.920414174,54.1612571176,15240 -3.9284973363,54.17050508660001,15240 -3.936087878,54.1798961556,15240 -3.9431781344,54.1894212578,15240 -3.949760909,54.1990711908,15240 -3.9558294816,54.208836625,15240 -3.961377616,54.2187081128,15240 -3.9663995673,54.2286760972,15240 -3.9708900887,54.23873092099999,15240 -3.9748444377,54.2488628357,15240 -3.9782583827,54.2590620111,15240 -3.981128208,54.2693185444,15240 -3.9834507192,54.27962247,15240 -3.9852232477,54.2899637685,15240 -3.9864436549,54.300332377,15240 -3.9871103357,54.31071819839999,15240 -3.9872222222,54.3211111111,15240 + + + + +
+ + EGD407 WARCOP + 543812N 0022047W -
543856N 0021445W -
543753N 0021402W -
543432N 0021545W -
543156N 0022043W -
543202N 0022209W -
543343N 0022536W -
543526N 0022419W -
543812N 0022047W
Upper limit: 13500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 10,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 13,500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01768-343224.

Remarks: SI 1981/623.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3463888889,54.6366666667,4114.8 -2.4052777778,54.5905555556,4114.8 -2.4266666667,54.56194444440001,4114.8 -2.3691666667,54.5338888889,4114.8 -2.3452777778,54.5322222222,4114.8 -2.2625,54.5755555556,4114.8 -2.2338888889,54.6313888889,4114.8 -2.2458333333,54.64888888889999,4114.8 -2.3463888889,54.6366666667,4114.8 + + + + +
+ + EGD408 FELDOM + 542826N 0015159W -
542750N 0014921W -
542656N 0014654W -
542513N 0014819W -
542447N 0015004W -
542505N 0015159W -
542720N 0015350W -
542826N 0015159W
Upper limit: 5600 FT MSL
Lower limit: SFC
Class: Vertical Limits: 3000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 5600 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/ BVLOS) (less than 150 KTS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.

Remarks: SI 1976/566.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8663888889,54.47388888889999,1706.88 -1.8972222222,54.45555555560001,1706.88 -1.8663888889,54.4180555556,1706.88 -1.8344444444,54.4130555556,1706.88 -1.8052777778,54.4202777778,1706.88 -1.7816666667,54.4488888889,1706.88 -1.8225,54.4638888889,1706.88 -1.8663888889,54.47388888889999,1706.88 + + + + +
+ + EGD410 STRENSALL + A circle, 3000 FT radius, centred at 540136N 0010101W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01904-442966.

Remarks: SI 1972/246.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0169444444,54.03488188850001,304.8 -1.0197537238,54.0347136897,304.8 -1.0224479252,54.0342159834,304.8 -1.0249166926,54.03340915700001,304.8 -1.027058919,54.0323262586,304.8 -1.0287868913,54.0310116417,304.8 -1.0300298828,54.0295191457,304.8 -1.0307370464,54.0279098892,304.8 -1.0308794896,54.0262497647,304.8 -1.0304514472,54.0246067401,304.8 -1.0294705074,54.023048075,304.8 -1.0279768809,54.0216375685,304.8 -1.0260317464,54.0204329494,304.8 -1.0237147413,54.0194835154,304.8 -1.0211207007,54.018828118,304.8 -1.0183557787,54.01849357499999,304.8 -1.0155331101,54.01849357499999,304.8 -1.0127681882,54.018828118,304.8 -1.0101741476,54.0194835154,304.8 -1.0078571425,54.0204329494,304.8 -1.005912008,54.0216375685,304.8 -1.0044183814,54.023048075,304.8 -1.0034374417,54.0246067401,304.8 -1.0030093993,54.0262497647,304.8 -1.0031518424,54.0279098892,304.8 -1.0038590061,54.0295191457,304.8 -1.0051019976,54.0310116417,304.8 -1.0068299699,54.0323262586,304.8 -1.0089721963,54.03340915700001,304.8 -1.0114409637,54.0342159834,304.8 -1.0141351651,54.0347136897,304.8 -1.0169444444,54.03488188850001,304.8 + + + + +
+ + EGD412 STAXTON + 545800N 0002300W -
552500N 0010000E -
550400N 0012100E -
544545N 0005455E following the line of latitude to -
544545N 0000917W -
545800N 0002300W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives.

Service: SUAAIS: London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3833333333,54.96666666669999,3048 -0.1547222222,54.76250000000001,3048 -0.0018650794,54.76250000000001,3048 0.1509920635,54.76250000000001,3048 0.3038492063,54.76250000000001,3048 0.4567063492,54.76250000000001,3048 0.6095634921,54.76250000000001,3048 0.7624206349,54.76250000000001,3048 0.9152777778000001,54.76250000000001,3048 1.35,55.0666666667,3048 1,55.4166666667,3048 -0.3833333333,54.96666666669999,3048 + + + + +
+ + EGD442 BELLERBY + A circle, 2300 M radius, centred at 542039N 0015125W
Upper limit: 3000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) (less than 150 KTS).

Service: SUAAIS: Leeming Zone on 133.375 MHz when open; at other times London Information on 125.475 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01748-875502.

Remarks: SI 1984/1770.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8569444444,54.36482938370001,914.4000000000001 -1.8615629685,54.3646525232,914.4000000000001 -1.8661023509,54.3641249725,914.4000000000001 -1.8704848124,54.3632557713,914.4000000000001 -1.874635274,54.3620598126,914.4000000000001 -1.8784826481,54.3605575869,914.4000000000001 -1.8819610599,54.35877482949999,914.4000000000001 -1.8850109775,54.3567420778,914.4000000000001 -1.8875802316,54.3544941467,914.4000000000001 -1.8896249068,54.3520695308,914.4000000000001 -1.8911100904,54.3495097429,914.4000000000001 -1.8920104643,54.3468586027,914.4000000000001 -1.8923107321,54.34416148500001,914.4000000000001 -1.8920058734,54.3414645427,914.4000000000001 -1.8911012215,54.3388139166,914.4000000000001 -1.8896123644,54.3362549466,914.4000000000001 -1.8875648703,54.33383139639999,914.4000000000001 -1.8849938442,54.3315847065,914.4000000000001 -1.8819433222,54.3295532866,914.4000000000001 -1.8784655147,54.3277718611,914.4000000000001 -1.8746199127,54.3262708765,914.4000000000001 -1.8704722699,54.3250759836,914.4000000000001 -1.8660934821,54.32420760019999,914.4000000000001 -1.8615583776,54.3236805636,914.4000000000001 -1.8569444444,54.3235038785,914.4000000000001 -1.8523305113,54.3236805636,914.4000000000001 -1.8477954068,54.32420760019999,914.4000000000001 -1.8434166189,54.3250759836,914.4000000000001 -1.8392689762,54.3262708765,914.4000000000001 -1.8354233741,54.3277718611,914.4000000000001 -1.8319455667,54.3295532866,914.4000000000001 -1.8288950447,54.3315847065,914.4000000000001 -1.8263240186,54.33383139639999,914.4000000000001 -1.8242765245,54.3362549466,914.4000000000001 -1.8227876674,54.3388139166,914.4000000000001 -1.8218830155,54.3414645427,914.4000000000001 -1.8215781568,54.34416148500001,914.4000000000001 -1.8218784246,54.3468586027,914.4000000000001 -1.8227787985,54.3495097429,914.4000000000001 -1.8242639821,54.3520695308,914.4000000000001 -1.8263086573,54.3544941467,914.4000000000001 -1.8288779114,54.3567420778,914.4000000000001 -1.831927829,54.35877482949999,914.4000000000001 -1.8354062408,54.3605575869,914.4000000000001 -1.8392536149,54.3620598126,914.4000000000001 -1.8434040765,54.3632557713,914.4000000000001 -1.847786538,54.3641249725,914.4000000000001 -1.8523259204,54.3646525232,914.4000000000001 -1.8569444444,54.36482938370001,914.4000000000001 + + + + +
+ + EGD505 MAGILLIGAN + 551117N 0065827W -
551307N 0065423W -
551253N 0065133W -
551107N 0064948W -
551010N 0065158W -
551008N 0065633W -
551117N 0065827W
Upper limit: 6500 FT MSL
Lower limit: SFC
Class: Vertical Limits: 2000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 6500 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 02877-720029.

Remarks: SI 1940/949.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.9741666667,55.18805555559999,1981.2 -6.942499999999999,55.1688888889,1981.2 -6.866111111099999,55.16944444439999,1981.2 -6.83,55.1852777778,1981.2 -6.8591666667,55.2147222222,1981.2 -6.9063888889,55.21861111110001,1981.2 -6.9741666667,55.18805555559999,1981.2 + + + + +
+ + EGD508 RIDSDALE + A circle, 1200 M radius, centred at 550845N 0021007W
Upper limit: 4100 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUACS: Newcastle APP on 124.380 MHz. SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information: Range Reception, Tel: 01434-220952.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1686111111,55.1566124562,1249.68 -2.1719724508,55.1564391851,1249.68 -2.1752256692,55.1559249452,1249.68 -2.178266131,55.15508627719999,1249.68 -2.1809960593,55.15395015599999,1249.68 -2.1833276853,55.15255312059999,1249.68 -2.1851860725,55.15094009760001,1249.68 -2.186511525,55.14916295340001,1249.68 -2.1872615013,55.14727882470001,1249.68 -2.1874119744,55.14534827960001,1249.68 -2.1869581941,55.14343336949999,1249.68 -2.1859148286,55.1415956348,1249.68 -2.1843154823,55.13989412720001,1249.68 -2.182211607,55.1383835141,1249.68 -2.1796708423,55.13711232389999,1249.68 -2.1767748386,55.13612138940001,1249.68 -2.1736166351,55.1354425383,1249.68 -2.1702976739,55.1350975733,1249.68 -2.1669245483,55.1350975733,1249.68 -2.1636055872,55.1354425383,1249.68 -2.1604473836,55.13612138940001,1249.68 -2.15755138,55.13711232389999,1249.68 -2.1550106152,55.1383835141,1249.68 -2.1529067399,55.13989412720001,1249.68 -2.1513073936,55.1415956348,1249.68 -2.1502640281,55.14343336949999,1249.68 -2.1498102478,55.14534827960001,1249.68 -2.149960721,55.14727882470001,1249.68 -2.1507106972,55.14916295340001,1249.68 -2.1520361497,55.15094009760001,1249.68 -2.1538945369,55.15255312059999,1249.68 -2.1562261629,55.15395015599999,1249.68 -2.1589560912,55.15508627719999,1249.68 -2.161996553,55.1559249452,1249.68 -2.1652497714,55.1564391851,1249.68 -2.1686111111,55.1566124562,1249.68 + + + + +
+ + EGD509 CAMPBELTOWN + 551230N 0053900W following the line of latitude to -
551230N 0050636W -
550706N 0050700W -
545930N 0051542W -
545548N 0052800W -
550630N 0054300W -
551230N 0053900W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: CTF311 Operations, Tel: 01923-956371.

Danger Area Authority: HQ Navy.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.65,55.2083333333,16764 -5.7166666667,55.1083333333,16764 -5.4666666667,54.92999999999999,16764 -5.2616666667,54.9916666667,16764 -5.1166666667,55.1183333333,16764 -5.11,55.2083333333,16764 -5.245,55.2083333333,16764 -5.38,55.2083333333,16764 -5.515,55.2083333333,16764 -5.65,55.2083333333,16764 + + + + +
+ + EGD510A SPADEADAM + 551500N 0025256W -
550112N 0024453W -
550900N 0030000W -
551500N 0025400W -
551500N 0025256W
Upper limit: 15000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 15,000 FT ALT by NOTAM.

Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8821305556,55.25,4572 -2.9,55.25,4572 -3,55.15,4572 -2.7480777778,55.01992500000001,4572 -2.8821305556,55.25,4572 + + + + +
+ + EGD510B SPADEADAM + 551500N 0025256W -
551500N 0023951W -
550453N 0021743W -
550417N 0021717W -
550206N 0021640W -
550000N 0022752W -
550000N 0024235W -
550112N 0024453W -
551500N 0025256W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.

Activity: Electronic/optical hazards / High Energy Manoeuvres / Para Dropping / Balloons / Ordnance, Munitions Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8821305556,55.25,5486.400000000001 -2.7480777778,55.01992500000001,5486.400000000001 -2.7097222222,55.00000000000001,5486.400000000001 -2.4644444444,55.00000000000001,5486.400000000001 -2.2777777778,55.035,5486.400000000001 -2.2880555556,55.0713888889,5486.400000000001 -2.2952777778,55.0813888889,5486.400000000001 -2.6641666667,55.25,5486.400000000001 -2.8821305556,55.25,5486.400000000001 + + + + +
+ + EGD510C SPADEADAM + A circle, 1.5 NM radius, centred at 550243N 0023526W
Upper limit: 18000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 5500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 18,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUACS: Spadeadam on 128.725 MHz. SUAAIS: Newcastle APP on 124.380 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01697-749486/749488.

Remarks: When EGD510C is activated in isolation from EGD510B, Unmanned Aircraft System (BVLOS) operations are not permitted.
When EGD510B is activated by NOTAM, EGD510C will also be activated for the same period and to the same altitude.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.59065,55.0702401658,5486.400000000001 -2.5957932319,55.0700649075,5486.400000000001 -2.6008641309,55.0695415973,5486.400000000001 -2.6057913869,55.0686775946,5486.400000000001 -2.6105057207,55.0674850495,5486.400000000001 -2.614940863,55.0659807311,5486.400000000001 -2.6190344894,55.06418579,5486.400000000001 -2.6227290992,55.0621254604,5486.400000000001 -2.6259728243,55.05982870279999,5486.400000000001 -2.6287201577,55.0573277963,5486.400000000001 -2.6309325909,55.05465788240001,5486.400000000001 -2.6325791506,55.0518564705,5486.400000000001 -2.6336368295,55.04896290960001,5486.400000000001 -2.6340909028,55.0460178342,5486.400000000001 -2.6339351282,55.0430625935,5486.400000000001 -2.6331718261,55.0401386701,5486.400000000001 -2.6318118396,55.0372870984,5486.400000000001 -2.6298743751,55.0345478888,5486.400000000001 -2.6273867262,55.031959467,5486.400000000001 -2.6243838853,55.0295581366,5486.400000000001 -2.6209080484,55.02737757089999,5486.400000000001 -2.6170080203,55.025448342,5486.400000000001 -2.612738529,55.02379749459999,5486.400000000001 -2.6081594582,55.0224481674,5486.400000000001 -2.6033350102,55.0214192711,5486.400000000001 -2.5983328083,55.0207252243,5486.400000000001 -2.5932229534,55.0203757525,5486.400000000001 -2.5880770466,55.0203757525,5486.400000000001 -2.5829671917,55.0207252243,5486.400000000001 -2.5779649898,55.0214192711,5486.400000000001 -2.5731405418,55.0224481674,5486.400000000001 -2.568561471,55.02379749459999,5486.400000000001 -2.5642919797,55.025448342,5486.400000000001 -2.5603919516,55.02737757089999,5486.400000000001 -2.5569161147,55.0295581366,5486.400000000001 -2.5539132738,55.031959467,5486.400000000001 -2.5514256249,55.0345478888,5486.400000000001 -2.5494881604,55.0372870984,5486.400000000001 -2.5481281739,55.0401386701,5486.400000000001 -2.5473648718,55.0430625935,5486.400000000001 -2.5472090972,55.0460178342,5486.400000000001 -2.5476631705,55.04896290960001,5486.400000000001 -2.5487208494,55.0518564705,5486.400000000001 -2.5503674091,55.05465788240001,5486.400000000001 -2.5525798423,55.0573277963,5486.400000000001 -2.5553271757,55.05982870279999,5486.400000000001 -2.5585709008,55.0621254604,5486.400000000001 -2.5622655106,55.06418579,5486.400000000001 -2.566359137,55.0659807311,5486.400000000001 -2.5707942793,55.0674850495,5486.400000000001 -2.5755086131,55.0686775946,5486.400000000001 -2.5804358691,55.0695415973,5486.400000000001 -2.5855067681,55.0700649075,5486.400000000001 -2.59065,55.0702401658,5486.400000000001 + + + + +
+ + EGD512A OTTERBURN + 551418N 0020239W -
551054N 0021311W -
551615N 0022552W -
551857N 0022315W -
551525N 0021352W -
551418N 0020239W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.

Remarks: SI 1971/919 and SI 1980/38.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0441666667,55.2383333333,6705.599999999999 -2.2311111111,55.2569444444,6705.599999999999 -2.3875,55.31583333329999,6705.599999999999 -2.4311111111,55.2708333333,6705.599999999999 -2.2197222222,55.1816666667,6705.599999999999 -2.0441666667,55.2383333333,6705.599999999999 + + + + +
+ + EGD512B OTTERBURN + 552426N 0021355W -
551719N 0020336W -
551418N 0020239W -
551525N 0021352W -
551857N 0022315W -
552212N 0022009W -
552426N 0021355W
Upper limit: 25000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 18,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 25,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01912-394261.

Remarks: SI 1971/919 and SI 1980/38.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2319444444,55.40722222219999,7620 -2.3358333333,55.37,7620 -2.3875,55.31583333329999,7620 -2.2311111111,55.2569444444,7620 -2.0441666667,55.2383333333,7620 -2.06,55.2886111111,7620 -2.2319444444,55.40722222219999,7620 + + + + +
+ + EGD513A DRURIDGE BAY + 550200N 0010000W -
552000N 0010640W -
552000N 0002300W -
550200N 0004000W -
550200N 0010000W
Upper limit: FL230
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1,55.0333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -1,55.0333333333,7010.400000000001 + + + + +
+ + EGD513B DRURIDGE BAY + 554400N 0011543W -
554400N 0000726E -
552000N 0001700E -
550200N 0004000W -
552000N 0002300W -
552000N 0010640W -
554400N 0011543W
Upper limit: FL230
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2619444444,55.7333333333,7010.400000000001 -1.1111111111,55.3333333333,7010.400000000001 -0.3833333333,55.3333333333,7010.400000000001 -0.6666666667,55.0333333333,7010.400000000001 0.2833333333,55.3333333333,7010.400000000001 0.1238888889,55.7333333333,7010.400000000001 -1.2619444444,55.7333333333,7010.400000000001 + + + + +
+ + EGD513C DRURIDGE BAY + 555000N 0011800W -
555000N 0000500E -
552000N 0001700E -
550200N 0004000W -
550200N 0010000W -
555000N 0011800W
Upper limit: FL100
Lower limit: SFC
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 134.775 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3,55.8333333333,3048 -1,55.0333333333,3048 -0.6666666667,55.0333333333,3048 0.2833333333,55.3333333333,3048 0.08333333330000001,55.8333333333,3048 -1.3,55.8333333333,3048 + + + + +
+ + EGD514 COMBAT AIRSPACE + 564944N 0023059W -
561522N 0003908E -
554828N 0020148E -
542337N 0012225E -
550310N 0010229W -
550419N 0010503W thence anti-clockwise by the arc of a circle radius 21 NM centred on 550217N 0014123W to
551920N 0012007W -
551610N 0013433W -
551426N 0014100W -
551403N 0014229W -
552952N 0023047W -
553928N 0024212W -
560122N 0023945W -
561317N 0025226W -
563754N 0024601W -
564944N 0023059W
Upper limit: FL660
Lower limit: FL85
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives (OME) / Electrical/Optical Hazards.

Service: SUAAIS: Scottish Information on 119.875 MHz and London Information on 125.475 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,20116.8 -2.7668234167,56.6316858611,20116.8 -2.8739837778,56.22139349999999,20116.8 -2.6626117778,56.0226490556,20116.8 -2.7031990833,55.6578733611,20116.8 -2.5130380278,55.49769625,20116.8 -1.7079248333,55.2341564444,20116.8 -1.683344,55.24068008330001,20116.8 -1.5759322778,55.2693510278,20116.8 -1.3351568333,55.32227475,20116.8 -1.3196354763,55.3157079327,20116.8 -1.304490274,55.3088632909,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2753887059,55.29436858319999,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2223387981,55.26236881040001,20116.8 -1.2102274184,55.25378864080001,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1481271314,55.19810933120001,20116.8 -1.13963258,55.1882171739,20116.8 -1.1316917604,55.17817610270001,20116.8 -1.1243122408,55.16799621880001,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1056084054,55.13672661809999,20116.8 -1.1005380561,55.1260949743,20116.8 -1.096058024,55.1153767893,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0414236389,55.0526792778,20116.8 1.3735272222,54.3935690833,20116.8 2.0298775556,55.8078658611,20116.8 0.6521053333,56.2561136389,20116.8 -2.5163368333,56.8287937778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.22139349999999,2590.8 -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.683344,55.24068008330001,2590.8 -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.29436858319999,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.26236881040001,2590.8 -1.2102274184,55.25378864080001,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.19810933120001,2590.8 -1.13963258,55.1882171739,2590.8 -1.1316917604,55.17817610270001,2590.8 -1.1243122408,55.16799621880001,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.13672661809999,2590.8 -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5163368333,56.8287937778,2590.8 -2.7668234167,56.6316858611,2590.8 -2.7668234167,56.6316858611,20116.8 -2.5163368333,56.8287937778,20116.8 -2.5163368333,56.8287937778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.7668234167,56.6316858611,2590.8 -2.8739837778,56.22139349999999,2590.8 -2.8739837778,56.22139349999999,20116.8 -2.7668234167,56.6316858611,20116.8 -2.7668234167,56.6316858611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.8739837778,56.22139349999999,2590.8 -2.6626117778,56.0226490556,2590.8 -2.6626117778,56.0226490556,20116.8 -2.8739837778,56.22139349999999,20116.8 -2.8739837778,56.22139349999999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.6626117778,56.0226490556,2590.8 -2.7031990833,55.6578733611,2590.8 -2.7031990833,55.6578733611,20116.8 -2.6626117778,56.0226490556,20116.8 -2.6626117778,56.0226490556,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.7031990833,55.6578733611,2590.8 -2.5130380278,55.49769625,2590.8 -2.5130380278,55.49769625,20116.8 -2.7031990833,55.6578733611,20116.8 -2.7031990833,55.6578733611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -2.5130380278,55.49769625,2590.8 -1.7079248333,55.2341564444,2590.8 -1.7079248333,55.2341564444,20116.8 -2.5130380278,55.49769625,20116.8 -2.5130380278,55.49769625,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.7079248333,55.2341564444,2590.8 -1.683344,55.24068008330001,2590.8 -1.683344,55.24068008330001,20116.8 -1.7079248333,55.2341564444,20116.8 -1.7079248333,55.2341564444,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.683344,55.24068008330001,2590.8 -1.5759322778,55.2693510278,2590.8 -1.5759322778,55.2693510278,20116.8 -1.683344,55.24068008330001,20116.8 -1.683344,55.24068008330001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.5759322778,55.2693510278,2590.8 -1.3351568333,55.32227475,2590.8 -1.3351568333,55.32227475,20116.8 -1.5759322778,55.2693510278,20116.8 -1.5759322778,55.2693510278,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.3351568333,55.32227475,2590.8 -1.3196354763,55.3157079327,2590.8 -1.3196354763,55.3157079327,20116.8 -1.3351568333,55.32227475,20116.8 -1.3351568333,55.32227475,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.3196354763,55.3157079327,2590.8 -1.304490274,55.3088632909,2590.8 -1.304490274,55.3088632909,20116.8 -1.3196354763,55.3157079327,20116.8 -1.3196354763,55.3157079327,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.304490274,55.3088632909,2590.8 -1.2897364284,55.3017477663,2590.8 -1.2897364284,55.3017477663,20116.8 -1.304490274,55.3088632909,20116.8 -1.304490274,55.3088632909,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2897364284,55.3017477663,2590.8 -1.2753887059,55.29436858319999,2590.8 -1.2753887059,55.29436858319999,20116.8 -1.2897364284,55.3017477663,20116.8 -1.2897364284,55.3017477663,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2753887059,55.29436858319999,2590.8 -1.2614614361,55.2867332297,2590.8 -1.2614614361,55.2867332297,20116.8 -1.2753887059,55.29436858319999,20116.8 -1.2753887059,55.29436858319999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2614614361,55.2867332297,2590.8 -1.2479684983,55.2788494494,2590.8 -1.2479684983,55.2788494494,20116.8 -1.2614614361,55.2867332297,20116.8 -1.2614614361,55.2867332297,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2479684983,55.2788494494,2590.8 -1.2349233067,55.2707252331,2590.8 -1.2349233067,55.2707252331,20116.8 -1.2479684983,55.2788494494,20116.8 -1.2479684983,55.2788494494,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2349233067,55.2707252331,2590.8 -1.2223387981,55.26236881040001,2590.8 -1.2223387981,55.26236881040001,20116.8 -1.2349233067,55.2707252331,20116.8 -1.2349233067,55.2707252331,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2223387981,55.26236881040001,2590.8 -1.2102274184,55.25378864080001,2590.8 -1.2102274184,55.25378864080001,20116.8 -1.2223387981,55.26236881040001,20116.8 -1.2223387981,55.26236881040001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.2102274184,55.25378864080001,2590.8 -1.1986011112,55.2449934046,2590.8 -1.1986011112,55.2449934046,20116.8 -1.2102274184,55.25378864080001,20116.8 -1.2102274184,55.25378864080001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1986011112,55.2449934046,2590.8 -1.1874713062,55.2359919941,2590.8 -1.1874713062,55.2359919941,20116.8 -1.1986011112,55.2449934046,20116.8 -1.1986011112,55.2449934046,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1874713062,55.2359919941,2590.8 -1.1768489084,55.2267935037,2590.8 -1.1768489084,55.2267935037,20116.8 -1.1874713062,55.2359919941,20116.8 -1.1874713062,55.2359919941,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1768489084,55.2267935037,2590.8 -1.1667442882,55.2174072208,2590.8 -1.1667442882,55.2174072208,20116.8 -1.1768489084,55.2267935037,20116.8 -1.1768489084,55.2267935037,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1667442882,55.2174072208,2590.8 -1.1571672715,55.2078426155,2590.8 -1.1571672715,55.2078426155,20116.8 -1.1667442882,55.2174072208,20116.8 -1.1667442882,55.2174072208,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1571672715,55.2078426155,2590.8 -1.1481271314,55.19810933120001,2590.8 -1.1481271314,55.19810933120001,20116.8 -1.1571672715,55.2078426155,20116.8 -1.1571672715,55.2078426155,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1481271314,55.19810933120001,2590.8 -1.13963258,55.1882171739,2590.8 -1.13963258,55.1882171739,20116.8 -1.1481271314,55.19810933120001,20116.8 -1.1481271314,55.19810933120001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.13963258,55.1882171739,2590.8 -1.1316917604,55.17817610270001,2590.8 -1.1316917604,55.17817610270001,20116.8 -1.13963258,55.1882171739,20116.8 -1.13963258,55.1882171739,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1316917604,55.17817610270001,2590.8 -1.1243122408,55.16799621880001,2590.8 -1.1243122408,55.16799621880001,20116.8 -1.1316917604,55.17817610270001,20116.8 -1.1316917604,55.17817610270001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1243122408,55.16799621880001,2590.8 -1.1175010074,55.1576877554,2590.8 -1.1175010074,55.1576877554,20116.8 -1.1243122408,55.16799621880001,20116.8 -1.1243122408,55.16799621880001,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1175010074,55.1576877554,2590.8 -1.1112644597,55.1472610668,2590.8 -1.1112644597,55.1472610668,20116.8 -1.1175010074,55.1576877554,20116.8 -1.1175010074,55.1576877554,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1112644597,55.1472610668,2590.8 -1.1056084054,55.13672661809999,2590.8 -1.1056084054,55.13672661809999,20116.8 -1.1112644597,55.1472610668,20116.8 -1.1112644597,55.1472610668,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1056084054,55.13672661809999,2590.8 -1.1005380561,55.1260949743,2590.8 -1.1005380561,55.1260949743,20116.8 -1.1056084054,55.13672661809999,20116.8 -1.1056084054,55.13672661809999,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.1005380561,55.1260949743,2590.8 -1.096058024,55.1153767893,2590.8 -1.096058024,55.1153767893,20116.8 -1.1005380561,55.1260949743,20116.8 -1.1005380561,55.1260949743,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.096058024,55.1153767893,2590.8 -1.0921723192,55.1045827952,2590.8 -1.0921723192,55.1045827952,20116.8 -1.096058024,55.1153767893,20116.8 -1.096058024,55.1153767893,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0921723192,55.1045827952,2590.8 -1.0888843473,55.0937237913,2590.8 -1.0888843473,55.0937237913,20116.8 -1.0921723192,55.1045827952,20116.8 -1.0921723192,55.1045827952,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0888843473,55.0937237913,2590.8 -1.0861969081,55.0828106334,2590.8 -1.0861969081,55.0828106334,20116.8 -1.0888843473,55.0937237913,20116.8 -1.0888843473,55.0937237913,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0861969081,55.0828106334,2590.8 -1.0841121944,55.0718542222,2590.8 -1.0841121944,55.0718542222,20116.8 -1.0861969081,55.0828106334,20116.8 -1.0861969081,55.0828106334,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0841121944,55.0718542222,2590.8 -1.0414236389,55.0526792778,2590.8 -1.0414236389,55.0526792778,20116.8 -1.0841121944,55.0718542222,20116.8 -1.0841121944,55.0718542222,2590.8 + + + + + + relativeToGround + + + relativeToGround + + -1.0414236389,55.0526792778,2590.8 1.3735272222,54.3935690833,2590.8 1.3735272222,54.3935690833,20116.8 -1.0414236389,55.0526792778,20116.8 -1.0414236389,55.0526792778,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 1.3735272222,54.3935690833,2590.8 2.0298775556,55.8078658611,2590.8 2.0298775556,55.8078658611,20116.8 1.3735272222,54.3935690833,20116.8 1.3735272222,54.3935690833,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 2.0298775556,55.8078658611,2590.8 0.6521053333,56.2561136389,2590.8 0.6521053333,56.2561136389,20116.8 2.0298775556,55.8078658611,20116.8 2.0298775556,55.8078658611,2590.8 + + + + + + relativeToGround + + + relativeToGround + + 0.6521053333,56.2561136389,2590.8 -2.5163368333,56.8287937778,2590.8 -2.5163368333,56.8287937778,20116.8 0.6521053333,56.2561136389,20116.8 0.6521053333,56.2561136389,2590.8 + + + + + +
+ + EGD601 GARELOCHHEAD + 560805N 0044636W -
560505N 0044656W -
560440N 0044740W -
560547N 0044912W -
560706N 0044912W -
560805N 0044636W
Upper limit: 4000 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 119.875 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01412-248123.

Danger Area Authority: DIO.

Remarks: UAS BVLOS will not be conducted above 1500 FT ALT.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.7766666667,56.1347222222,1219.2 -4.82,56.11833333329999,1219.2 -4.82,56.0963888889,1219.2 -4.7944444444,56.0777777778,1219.2 -4.7822222222,56.0847222222,1219.2 -4.7766666667,56.1347222222,1219.2 + + + + +
+ + EGD604 BARRY BUDDON + 562849N 0024849W -
562957N 0024010W -
562735N 0023943W -
562738N 0024829W -
562849N 0024849W
Upper limit: 9000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 9000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Para Dropping / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Leuchars APP on 126.500 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-103426.

Remarks: SI 1973/1428. UAS BVLOS will not be conducted above 3000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.813611111100001,56.4802777778,2743.2 -2.8080555556,56.4605555556,2743.2 -2.6619444444,56.45972222219999,2743.2 -2.6694444444,56.49916666670001,2743.2 -2.813611111100001,56.4802777778,2743.2 + + + + +
+ + EGD613A CENTRAL COMPLEX + 574421N 0002631E -
571940N 0004851E -
564725N 0013559W -
571447N 0014618W -
574421N 0002631E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,20116.8 -1.7715583333,57.2462805556,20116.8 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.4419305556,57.7391472222,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,3048 -1.7715583333,57.2462805556,3048 -1.5996,56.7901638889,3048 0.8140888889,57.32785,3048 0.4419305556,57.7391472222,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.4419305556,57.7391472222,3048 -1.7715583333,57.2462805556,3048 -1.7715583333,57.2462805556,20116.8 0.4419305556,57.7391472222,20116.8 0.4419305556,57.7391472222,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.7715583333,57.2462805556,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 -1.7715583333,57.2462805556,20116.8 -1.7715583333,57.2462805556,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 0.8140888889,57.32785,3048 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 0.4419305556,57.7391472222,3048 0.4419305556,57.7391472222,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048 + + + + + +
+ + EGD613B CENTRAL COMPLEX + 571940N 0004851E -
565256N 0011225E -
564725N 0013559W -
571940N 0004851E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,20116.8 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 0.8140888889,57.32785,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 -1.5996,56.7901638889,3048 1.2068416667,56.8823361111,3048 0.8140888889,57.32785,3048 + + + + + + relativeToGround + + + relativeToGround + + 0.8140888889,57.32785,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 0.8140888889,57.32785,20116.8 0.8140888889,57.32785,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 0.8140888889,57.32785,3048 0.8140888889,57.32785,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + +
+ + EGD613C CENTRAL COMPLEX + 565256N 0011225E -
561750N 0012507W -
564725N 0013559W -
565256N 0011225E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,20116.8 -1.5996,56.7901638889,20116.8 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.5996,56.7901638889,3048 -1.4184805556,56.2971694444,3048 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.5996,56.7901638889,3048 -1.5996,56.7901638889,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.5996,56.7901638889,3048 -1.4184805556,56.2971694444,3048 -1.4184805556,56.2971694444,20116.8 -1.5996,56.7901638889,20116.8 -1.5996,56.7901638889,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.4184805556,56.2971694444,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048 + + + + + +
+ + EGD613D CENTRAL COMPLEX + 565256N 0011225E -
560344N 0015411E -
560509N 0002907W -
561750N 0012507W -
565256N 0011225E
Upper limit: FL660
Lower limit: FL100
Class: AMC - Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions and Explosives.

Service: SUAAIS: Swanwick Military on 136.375 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,20116.8 -1.4184805556,56.2971694444,20116.8 -0.4851527778,56.0857027778,20116.8 1.9031472222,56.0623555556,20116.8 1.2068416667,56.8823361111,20116.8 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.4184805556,56.2971694444,3048 -0.4851527778,56.0857027778,3048 1.9031472222,56.0623555556,3048 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.2068416667,56.8823361111,3048 -1.4184805556,56.2971694444,3048 -1.4184805556,56.2971694444,20116.8 1.2068416667,56.8823361111,20116.8 1.2068416667,56.8823361111,3048 + + + + + + relativeToGround + + + relativeToGround + + -1.4184805556,56.2971694444,3048 -0.4851527778,56.0857027778,3048 -0.4851527778,56.0857027778,20116.8 -1.4184805556,56.2971694444,20116.8 -1.4184805556,56.2971694444,3048 + + + + + + relativeToGround + + + relativeToGround + + -0.4851527778,56.0857027778,3048 1.9031472222,56.0623555556,3048 1.9031472222,56.0623555556,20116.8 -0.4851527778,56.0857027778,20116.8 -0.4851527778,56.0857027778,3048 + + + + + + relativeToGround + + + relativeToGround + + 1.9031472222,56.0623555556,3048 1.2068416667,56.8823361111,3048 1.2068416667,56.8823361111,20116.8 1.9031472222,56.0623555556,20116.8 1.9031472222,56.0623555556,3048 + + + + + +
+ + EGD701A HEBRIDES + 573347N 0074803W -
572253N 0072531W -
572324N 0072233W -
572147N 0072116W -
571056N 0072253W -
571034N 0073131W -
570200N 0073421W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
573347N 0074803W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.800833333299999,57.5630555556,30449.52 -7.8147936092,57.5556144002,30449.52 -7.8282732985,57.54792286990001,30449.52 -7.841261266,57.5399919141,30449.52 -7.8537430548,57.5318305591,30449.52 -7.8657048125,57.5234480871,30449.52 -7.877133306,57.51485402520001,30449.52 -7.8880159355,57.5060581345,30449.52 -7.8983407475,57.4970703978,30449.52 -7.9080964477,57.4879010084,30449.52 -7.9172724118,57.4785603579,30449.52 -7.925858696199999,57.4690590239,30449.52 -7.9338460477,57.4594077576,30449.52 -7.9412259119,57.4496174713,30449.52 -7.9479904416,57.4396992258,30449.52 -7.954132502800001,57.4296642173,30449.52 -7.9596456814,57.41952376460001,30449.52 -7.9645242879,57.40928929609999,30449.52 -7.9687633616,57.3989723365,30449.52 -7.972358674,57.3885844937,30449.52 -7.975306731,57.37813744549999,30449.52 -7.9776047746,57.36764292620001,30449.52 -7.9792507833,57.3571127135,30449.52 -7.980243472200001,57.3465586152,30449.52 -7.9805822915,57.3359924554,30449.52 -7.980267425,57.325426062,30449.52 -7.979299787,57.3148712527,30449.52 -7.9776810193,57.3043398224,30449.52 -7.9754134861,57.2938435297,30449.52 -7.9725002697,57.28339408400001,30449.52 -7.9689451642,57.2730031328,30449.52 -7.9647526688,57.2626822485,30449.52 -7.959927980999999,57.2524429158,30449.52 -7.954476987700001,57.2422965194,30449.52 -7.9484062576,57.2322543314,30449.52 -7.9417230308,57.222327499,30449.52 -7.934435209299999,57.2125270325,30449.52 -7.9265513463,57.2028637936,30449.52 -7.9180806346,57.1933484835,30449.52 -7.9090328952,57.1839916314,30449.52 -7.8994185645,57.1748035833,30449.52 -7.8892486813,57.1657944914,30449.52 -7.8785348735,57.1569743024,30449.52 -7.8672893439,57.148352748,30449.52 -7.8555248557,57.1399393337,30449.52 -7.8432547174,57.1317433295,30449.52 -7.8304927676,57.12377375980001,30449.52 -7.8172533586,57.116039394,30449.52 -7.803551340600001,57.1085487375,30449.52 -7.7894020448,57.1013100226,30449.52 -7.7748212661,57.0943312,30449.52 -7.7598252458,57.0876199308,30449.52 -7.7444306541,57.0811835783,30449.52 -7.7286545713,57.07502920040001,30449.52 -7.712514469999999,57.06916354269999,30449.52 -7.696028196,57.06359303100001,30449.52 -7.679213949500001,57.058323765,30449.52 -7.6620902657,57.0533615124,30449.52 -7.644675995300001,57.0487117023,30449.52 -7.626990285100001,57.0443794202,30449.52 -7.6090525576,57.0403694026,30449.52 -7.5908824912,57.0366860321,30449.52 -7.5725,57.03333333329999,30449.52 -7.5252777778,57.1761111111,30449.52 -7.381388888900001,57.18222222219999,30449.52 -7.3544444444,57.3630555556,30449.52 -7.3758333333,57.39000000000001,30449.52 -7.4252777778,57.3813888889,30449.52 -7.800833333299999,57.5630555556,30449.52 + + + + +
+ + EGD701B HEBRIDES + 570200N 0073421W -
565713N 0073556W -
571703N 0092047W -
574801N 0092039W -
574514N 0083032W -
574224N 0080606W -
573347N 0074803W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
570200N 0073421W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.5725,57.03333333329999,30449.52 -7.5908806376,57.0366888943,30449.52 -7.609050530599999,57.04037222969999,30449.52 -7.626988086899999,57.04438220909999,30449.52 -7.6446736282,57.04871444989999,30449.52 -7.6620877322,57.05336421570001,30449.52 -7.6792112525,57.058326421,30449.52 -7.6960253382,57.0635956367,30449.52 -7.7125114546,57.06916609529999,30449.52 -7.7286514014,57.07503169700001,30449.52 -7.7444273331,57.0811860162,30449.52 -7.7598217773,57.0876223072,30449.52 -7.7748176538,57.0943335124,30449.52 -7.7893982926,57.1013122683,30449.52 -7.8035474526,57.10855091410001,30449.52 -7.817249339,57.11604149910001,30449.52 -7.830488620599999,57.12377579100001,30449.52 -7.8432504477,57.1317452846,30449.52 -7.8555204677,57.13994121040001,30449.52 -7.8672848425,57.1483545443,30449.52 -7.8785302635,57.1569760164,30449.52 -7.8892439677,57.165796121,30449.52 -7.899413752499999,57.1748051268,30449.52 -7.9090279901,57.1839930869,30449.52 -7.9180756416,57.1933498495,30449.52 -7.9265462709,57.2028650685,30449.52 -7.9344300571,57.2125282149,30449.52 -7.9417178074,57.2223285875,30449.52 -7.9484009688,57.2322553248,30449.52 -7.954471639299999,57.2422974166,30449.52 -7.9599225788,57.25244371580001,30449.52 -7.964747219,57.2626829503,30449.52 -7.9689396726,57.27300373569999,30449.52 -7.972494742500001,57.2833945872,30449.52 -7.9754079293,57.2938439326,30449.52 -7.9776754391,57.30434012450001,30449.52 -7.9792941897,57.3148714537,30449.52 -7.9802618168,57.3254261616,30449.52 -7.9805766787,57.33599245359999,30449.52 -7.980237860999999,57.3465585118,30449.52 -7.9792451801,57.35711250869999,30449.52 -7.9775991856,57.3676426201,30449.52 -7.975301162499999,57.3781370385,30449.52 -7.972353132200001,57.3885839862,30449.52 -7.9687578529,57.3989717291,30449.52 -7.964518818399999,57.4092885894,30449.52 -7.9596402574,57.4195229594,30449.52 -7.9541271304,57.42966331440001,30449.52 -7.9479851269,57.4396982262,30449.52 -7.941220660999999,57.4496163762,30449.52 -7.933840866500001,57.4594065681,30449.52 -7.9258535907,57.46905774129999,30449.52 -7.9172673878,57.4785589837,30449.52 -7.908091510899999,57.4878995441,30449.52 -7.898335903599999,57.49706884499999,30449.52 -7.88801119,57.5060564949,30449.52 -7.877128664499999,57.5148523008,30449.52 -7.8657002803,57.5234462797,30449.52 -7.8537386371,57.5318286708,30449.52 -7.841256967800001,57.53998994690001,30449.52 -7.8282691249,57.547920826,30449.52 -7.814789565,57.555612282,30449.52 -7.800833333299999,57.5630555556,30449.52 -8.1016944444,57.7065416667,30449.52 -8.508827777800001,57.7539222222,30449.52 -9.3442027778,57.80035277780001,30449.52 -9.346377777800001,57.2840638889,30449.52 -7.5988888889,56.9536111111,30449.52 -7.5725,57.03333333329999,30449.52 + + + + +
+ + EGD701C HEBRIDES + 574801N 0092039W -
575639N 0081032W -
575154N 0074532W -
573809N 0073422W thence anti-clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to
573347N 0074803W -
574224N 0080606W -
574514N 0083032W -
574801N 0092039W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.3442027778,57.80035277780001,30449.52 -8.508827777800001,57.7539222222,30449.52 -8.1016944444,57.7065416667,30449.52 -7.800833333299999,57.5630555556,30449.52 -7.786893946,57.5700722445,30449.52 -7.772476361,57.5768067724,30449.52 -7.7576539429,57.58328442349999,30449.52 -7.7424424392,57.5894982237,30449.52 -7.7268580417,57.59544147929999,30449.52 -7.7109173688,57.601107785,30449.52 -7.6946374473,57.6064910309,30449.52 -7.6780356935,57.6115854099,30449.52 -7.6611298942,57.6163854238,30449.52 -7.6439381861,57.6208858901,30449.52 -7.6264790362,57.625081948,30449.52 -7.608771220300001,57.6289690637,30449.52 -7.590833802000001,57.63254303570001,30449.52 -7.572686111099999,57.6358,30449.52 -7.7588888889,57.865,30449.52 -8.175577777799999,57.9442055556,30449.52 -9.3442027778,57.80035277780001,30449.52 + + + + +
+ + EGD701D HEBRIDES + 571703N 0092047W -
565801N 0074000W -
564302N 0074000W -
565603N 0090000W -
571703N 0092047W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.346377777800001,57.2840638889,30449.52 -9,56.9342638889,30449.52 -7.666666666699999,56.7172722222,30449.52 -7.666666666699999,56.9669944444,30449.52 -9.346377777800001,57.2840638889,30449.52 + + + + +
+ + EGD701E HEBRIDES + 582859N 0094100W following the line of latitude to -
582859N 0084939W -
574923N 0071500W -
574128N 0073703W -
575154N 0074532W -
575639N 0081032W -
575411N 0083112W -
580439N 0085353W -
582859N 0094100W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -9.683422222200001,58.4831388889,30449.52 -8.898055555599999,58.0775,30449.52 -8.520127777800001,57.9030305556,30449.52 -8.175577777799999,57.9442055556,30449.52 -7.7588888889,57.865,30449.52 -7.6173694444,57.6910777778,30449.52 -7.250000000000001,57.82314722220001,30449.52 -8.8276361111,58.4831388889,30449.52 -8.9987933333,58.4831388889,30449.52 -9.1699505556,58.4831388889,30449.52 -9.3411077778,58.4831388889,30449.52 -9.512264999999999,58.4831388889,30449.52 -9.683422222200001,58.4831388889,30449.52 + + + + +
+ + EGD701F HEBRIDES + 593000N 0100000W -
584715N 0074914W -
582525N 0070835W -
574923N 0071500W -
582859N 0084939W following the line of latitude to -
582859N 0100000W -
593000N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,59.5,30449.52 -10,58.4831388889,30449.52 -9.832519444400001,58.4831388889,30449.52 -9.6650388889,58.4831388889,30449.52 -9.497558333300001,58.4831388889,30449.52 -9.3300777778,58.4831388889,30449.52 -9.162597222200001,58.4831388889,30449.52 -8.9951166667,58.4831388889,30449.52 -8.8276361111,58.4831388889,30449.52 -7.250000000000001,57.82314722220001,30449.52 -7.1430638889,58.4235972222,30449.52 -7.820622222200001,58.7873638889,30449.52 -10,59.5,30449.52 + + + + +
+ + EGD701G HEBRIDES + 582859N 0100000W following the line of latitude to -
582859N 0094100W -
580439N 0085353W -
575411N 0083112W -
574801N 0092039W -
571703N 0092047W -
573301N 0100000W -
582859N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,58.4831388889,30449.52 -10,57.5501444444,30449.52 -9.346377777800001,57.2840638889,30449.52 -9.3442027778,57.80035277780001,30449.52 -8.520127777800001,57.9030305556,30449.52 -8.898055555599999,58.0775,30449.52 -9.683422222200001,58.4831388889,30449.52 -9.8417111111,58.4831388889,30449.52 -10,58.4831388889,30449.52 + + + + +
+ + EGD701H HEBRIDES + 573301N 0100000W -
571703N 0092047W -
565603N 0090000W -
571500N 0100000W -
573301N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,57.5501444444,30449.52 -10,57.25,30449.52 -9,56.9342638889,30449.52 -9.346377777800001,57.2840638889,30449.52 -10,57.5501444444,30449.52 + + + + +
+ + EGD701I HEBRIDES + 571500N 0100000W -
565603N 0090000W -
564302N 0074000W -
563510N 0074307W -
563524N 0083728W -
564548N 0100000W -
571500N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,57.25,30449.52 -10,56.7633694444,30449.52 -8.624513888899999,56.5898861111,30449.52 -7.7185305556,56.5859805556,30449.52 -7.666666666699999,56.7172722222,30449.52 -9,56.9342638889,30449.52 -10,57.25,30449.52 + + + + +
+ + EGD701J HEBRIDES + 564548N 0100000W -
563524N 0083728W -
563510N 0074307W -
560339N 0074415W -
563523N 0100000W -
564548N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.7633694444,30449.52 -10,56.5896416667,30449.52 -7.7374527778,56.0608027778,30449.52 -7.7185305556,56.5859805556,30449.52 -8.624513888899999,56.5898861111,30449.52 -10,56.7633694444,30449.52 + + + + +
+ + EGD701K HEBRIDES + 563523N 0100000W -
560339N 0074415W -
555107N 0080000W following the line of latitude to -
555107N 0080331W -
562630N 0100000W -
563523N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.5896416667,30449.52 -10,56.4417388889,30449.52 -8.0585555556,55.8519,30449.52 -8,55.8519,30449.52 -7.7374527778,56.0608027778,30449.52 -10,56.5896416667,30449.52 + + + + +
+ + EGD701L HEBRIDES + 562630N 0100000W -
560435N 0084640W -
560530N 0100000W -
562630N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.4417388889,30449.52 -10,56.09176111110001,30449.52 -8.7777972222,56.0762722222,30449.52 -10,56.4417388889,30449.52 + + + + +
+ + EGD701M HEBRIDES + 560530N 0100000W -
560435N 0084640W -
555107N 0080331W following the line of latitude to -
555107N 0080000W -
554000N 0080000W following the line of latitude to -
554000N 0092508W -
554516N 0100000W -
560530N 0100000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -10,56.09176111110001,30449.52 -10,55.7545083333,30449.52 -9.4188888889,55.6666666667,30449.52 -9.261234567900001,55.6666666667,30449.52 -9.1035802469,55.6666666667,30449.52 -8.945925925899999,55.6666666667,30449.52 -8.7882716049,55.6666666667,30449.52 -8.630617284,55.6666666667,30449.52 -8.472962963000001,55.6666666667,30449.52 -8.315308642,55.6666666667,30449.52 -8.157654321000001,55.6666666667,30449.52 -8,55.6666666667,30449.52 -8,55.8519,30449.52 -8.0585555556,55.8519,30449.52 -8.7777972222,56.0762722222,30449.52 -10,56.09176111110001,30449.52 + + + + +
+ + EGD701N HEBRIDES + 563148N 0114510W -
560530N 0100000W -
554516N 0100000W -
555352N 0110000W -
563148N 0114510W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -11.7529138889,56.53005,30449.52 -11,55.8977805556,30449.52 -10,55.7545083333,30449.52 -10,56.09176111110001,30449.52 -11.7529138889,56.53005,30449.52 + + + + +
+ + EGD701O HEBRIDES + 570000N 0120000W -
562630N 0100000W -
560530N 0100000W -
563148N 0114510W -
564357N 0120000W -
570000N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57,30449.52 -12,56.7324472222,30449.52 -11.7529138889,56.53005,30449.52 -10,56.09176111110001,30449.52 -10,56.4417388889,30449.52 -12,57,30449.52 + + + + +
+ + EGD701P HEBRIDES + 572125N 0120000W -
565038N 0104118W -
564548N 0100000W -
562630N 0100000W -
570000N 0120000W -
572125N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57.3568694444,30449.52 -12,57,30449.52 -10,56.4417388889,30449.52 -10,56.7633694444,30449.52 -10.6883611111,56.8439194444,30449.52 -12,57.3568694444,30449.52 + + + + +
+ + EGD701Q HEBRIDES + 572125N 0120000W -
571500N 0100000W -
564548N 0100000W -
565038N 0104118W -
572125N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,57.3568694444,30449.52 -10.6883611111,56.8439194444,30449.52 -10,56.7633694444,30449.52 -10,57.25,30449.52 -12,57.3568694444,30449.52 + + + + +
+ + EGD701R HEBRIDES + 580135N 0120000W -
573301N 0100000W -
571500N 0100000W -
572125N 0120000W -
580135N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,58.0264222222,30449.52 -12,57.3568694444,30449.52 -10,57.25,30449.52 -10,57.5501444444,30449.52 -12,58.0264222222,30449.52 + + + + +
+ + EGD701S HEBRIDES + 584514N 0120000W -
582859N 0100000W -
573301N 0100000W -
580135N 0120000W -
584514N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,58.7539083333,30449.52 -12,58.0264222222,30449.52 -10,57.5501444444,30449.52 -10,58.4831388889,30449.52 -12,58.7539083333,30449.52 + + + + +
+ + EGD701T HEBRIDES + 593000N 0120000W following the line of latitude to -
593000N 0100000W -
582859N 0100000W -
584514N 0120000W -
593000N 0120000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -12,59.5,30449.52 -12,58.7539083333,30449.52 -10,58.4831388889,30449.52 -10,59.5,30449.52 -10.1666666667,59.5,30449.52 -10.3333333333,59.5,30449.52 -10.5,59.5,30449.52 -10.6666666667,59.5,30449.52 -10.8333333333,59.5,30449.52 -11,59.5,30449.52 -11.1666666667,59.5,30449.52 -11.3333333333,59.5,30449.52 -11.5,59.5,30449.52 -11.6666666667,59.5,30449.52 -11.8333333333,59.5,30449.52 -12,59.5,30449.52 + + + + +
+ + EGD701U HEBRIDES + 590000N 0130000W -
593000N 0120000W -
584514N 0120000W -
585236N 0130000W -
590000N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,59,30449.52 -13,58.8765361111,30449.52 -12,58.7539083333,30449.52 -12,59.5,30449.52 -13,59,30449.52 + + + + +
+ + EGD701V HEBRIDES + 585236N 0130000W -
584514N 0120000W -
580135N 0120000W -
581454N 0130000W -
585236N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,58.8765361111,30449.52 -13,58.2481972222,30449.52 -12,58.0264222222,30449.52 -12,58.7539083333,30449.52 -13,58.8765361111,30449.52 + + + + +
+ + EGD701W HEBRIDES + 581454N 0130000W -
580135N 0120000W -
572125N 0120000W -
573126N 0130000W -
581454N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,58.2481972222,30449.52 -13,57.5239055556,30449.52 -12,57.3568694444,30449.52 -12,58.0264222222,30449.52 -13,58.2481972222,30449.52 + + + + +
+ + EGD701X HEBRIDES + 573126N 0130000W -
572125N 0120000W -
564357N 0120000W -
573126N 0130000W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -13,57.5239055556,30449.52 -12,56.7324472222,30449.52 -12,57.3568694444,30449.52 -13,57.5239055556,30449.52 + + + + +
+ + EGD701Y HEBRIDES + 573809N 0073422W -
572324N 0072233W -
572253N 0072531W -
573347N 0074803W thence clockwise by the arc of a circle radius 19 NM centred on 572004N 0072347W to -
573809N 0073422W
Upper limit: UNL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.572686111099999,57.6358,30449.52 -7.5908058302,57.63250052330001,30449.52 -7.608740671100001,57.6289270654,30449.52 -7.6264459435,57.6250405088,30449.52 -7.643902586399999,57.6208450543,30449.52 -7.6610918269,57.61634523510001,30449.52 -7.677995200800001,57.6115459113,30449.52 -7.6945945737,57.6064522647,30449.52 -7.710872161599999,57.6010697925,30449.52 -7.726810550800001,57.5954043011,30449.52 -7.7423927169,57.58946189949999,30449.52 -7.7576020438,57.58324899199999,30449.52 -7.7724223421,57.5767722714,30449.52 -7.786837866700001,57.5700387107,30449.52 -7.800833333299999,57.5630555556,30449.52 -7.4252777778,57.3813888889,30449.52 -7.3758333333,57.39000000000001,30449.52 -7.572686111099999,57.6358,30449.52 + + + + +
+ + EGD702 FORT GEORGE + 573617N 0040047W -
573449N 0040128W -
573440N 0040257W -
573456N 0040438W -
573534N 0040338W -
573617N 0040047W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: Inverness APP/Tower on 122.605 MHz when open; at other times Scottish Information on 134.850 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01313-108124/108114.

Remarks: SI 1940/30.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0130555556,57.6047222222,640.08 -4.0605555556,57.5927777778,640.08 -4.0772222222,57.5822222222,640.08 -4.0491666667,57.57777777780001,640.08 -4.0244444444,57.5802777778,640.08 -4.0130555556,57.6047222222,640.08 + + + + +
+ + EGD703 TAIN + 575224N 0033030W -
575054N 0034630W -
574500N 0035500W -
574500N 0040254W -
575136N 0040812W -
580324N 0034436W -
580700N 0033700W -
580300N 0033000W -
575224N 0033000W -
575224N 0033030W
Upper limit: 22000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 15,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 22,000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Para Dropping / Electronic/Optical Hazards.

Service: SUACS: Tain Range on 122.750 MHz when open. SUAAIS: Tain Range on 122.750 MHz when open; at other times Scottish Information on 134.850 MHz.

Contact: Pre-flight information / Booking: Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: Aircraft wishing to use Dornoch or Easter Aerodromes during range opening hours are to contact Tain Range on 122.750 MHz prior to entering the range. Associated aircraft operations outside area boundary. SI 1940/684. UAS BVLOS will not be conducted above 2000 FT ALT.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5083333333,57.8733333333,6705.599999999999 -3.5,57.8733333333,6705.599999999999 -3.5,58.05,6705.599999999999 -3.6166666667,58.1166666667,6705.599999999999 -3.7433333333,58.0566666667,6705.599999999999 -4.1366666667,57.86,6705.599999999999 -4.0483333333,57.75000000000001,6705.599999999999 -3.9166666667,57.75000000000001,6705.599999999999 -3.775,57.8483333333,6705.599999999999 -3.5083333333,57.8733333333,6705.599999999999 + + + + +
+ + EGD704 HEBRIDES + 573727N 0071811W -
573143N 0071055W -
572625N 0072457W -
573305N 0073017W -
573727N 0071811W
Upper limit: 10000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Target Towing / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Ordnance, Munitions and Explosives / Para Dropping / Balloons / Electronic/Optical Hazards.

Service: SUACS: Benbecula Approach on 119.205 MHz when open. SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01870-604449.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.303055555600001,57.6241666667,3048 -7.504722222199999,57.5513888889,3048 -7.4158333333,57.44027777779999,3048 -7.181944444400001,57.52861111110001,3048 -7.303055555600001,57.6241666667,3048 + + + + +
+ + EGD710 RAASAY + 572200N 0054927W -
572200N 0055935W - then along the east coast of Raasay and Rona in an northerly direction to
573500N 0055800W -
573800N 0055800W -
573800N 0055000W -
573445N 0055000W - then along the west coast of the Applecross peninsula in an southerly direction to -
572200N 0054927W
Upper limit: 1500 FT MSL
Lower limit: SFC
Class: Activity: Ordnance, Munitions and Explosives / Electronic/Optical Hazards / Unmanned Aircraft System (VLOS/BVLOS).

Service: SUAAIS: Scottish Information on 127.275 MHz.

Contact: Pre-flight information: Range Control, Tel: 01397-436720.

Remarks: SI 2016/654.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.824166666699999,57.3666666667,457.2 -5.8226555556,57.36760277779999,457.2 -5.8224527778,57.36886666669999,457.2 -5.8234638889,57.3721638889,457.2 -5.8240722222,57.37322499999999,457.2 -5.8225916667,57.3749777778,457.2 -5.8243083333,57.3770833333,457.2 -5.8253972222,57.37795,457.2 -5.8264361111,57.3815166667,457.2 -5.825166666699999,57.38371111110001,457.2 -5.8259833333,57.3867444444,457.2 -5.826611111100001,57.3879833333,457.2 -5.8284305556,57.3894583333,457.2 -5.829925,57.39085,457.2 -5.8288083333,57.39197222220001,457.2 -5.8265416667,57.39130555560001,457.2 -5.8242083333,57.3913027778,457.2 -5.8240833333,57.3894555556,457.2 -5.8210777778,57.3876138889,457.2 -5.818275,57.3894972222,457.2 -5.8188222222,57.3915472222,457.2 -5.8205416667,57.3936527778,457.2 -5.820855555599999,57.3950833333,457.2 -5.818997222200001,57.39801666670001,457.2 -5.8183916667,57.4014888889,457.2 -5.8152333333,57.4009194444,457.2 -5.8142611111,57.399725,457.2 -5.8131638889,57.39783333329999,457.2 -5.8121638889,57.39509444439999,457.2 -5.8105222222,57.3954944444,457.2 -5.8097055556,57.393875,457.2 -5.8080416667,57.3940694444,457.2 -5.8062666667,57.39188333329999,457.2 -5.803124999999999,57.391125,457.2 -5.803124999999999,57.3927444444,457.2 -5.8058944444,57.3953583333,457.2 -5.807980555600001,57.3961916667,457.2 -5.8087861111,57.39913611109999,457.2 -5.8064416667,57.3990277778,457.2 -5.8055472222,57.4000444444,457.2 -5.807688888899999,57.4014166667,457.2 -5.808275,57.4054472222,457.2 -5.8103805556,57.4064611111,457.2 -5.813627777799999,57.4072611111,457.2 -5.815799999999999,57.4105222222,457.2 -5.818783333299999,57.4119611111,457.2 -5.823711111100001,57.4112722222,457.2 -5.8244055556,57.41313888889999,457.2 -5.8238833333,57.4161222222,457.2 -5.8244111111,57.41799444439999,457.2 -5.8238777778,57.41926944439999,457.2 -5.8217138889,57.4224833333,457.2 -5.821116666699999,57.42475,457.2 -5.818416666700001,57.4276194444,457.2 -5.8169944444,57.42838055559999,457.2 -5.8152527778,57.4308611111,457.2 -5.8148944444,57.4322222222,457.2 -5.8130111111,57.4333583333,457.2 -5.8099277778,57.43416944439999,457.2 -5.8050638889,57.43710555560001,457.2 -5.8060277778,57.4399527778,457.2 -5.8101388889,57.4409972222,457.2 -5.8113777778,57.4416805556,457.2 -5.816375,57.44323611110001,457.2 -5.8245111111,57.4412805556,457.2 -5.8296361111,57.4408555556,457.2 -5.8365972222,57.4404638889,457.2 -5.839950000000001,57.44063055560001,457.2 -5.8442444444,57.4402305556,457.2 -5.849816666700001,57.4408694444,457.2 -5.8519055556,57.4417055556,457.2 -5.855736111100001,57.444825,457.2 -5.8582361111,57.44798611110001,457.2 -5.8597777778,57.4515361111,457.2 -5.860766666699999,57.4545638889,457.2 -5.8599416667,57.457825,457.2 -5.860183333300001,57.4616833333,457.2 -5.8628055556,57.4643916667,457.2 -5.8637527778,57.4670611111,457.2 -5.8619277778,57.4687333333,457.2 -5.862116666700001,57.4705277778,457.2 -5.8678166667,57.4691833333,457.2 -5.8704361111,57.4702722222,457.2 -5.871280555599999,57.47510277779999,457.2 -5.867447222199999,57.4798944444,457.2 -5.8674805556,57.48493055560001,457.2 -5.86865,57.4896611111,457.2 -5.866241666699999,57.4921611111,457.2 -5.8660944444,57.49549444440001,457.2 -5.8653222222,57.497675,457.2 -5.8675888889,57.5017416667,457.2 -5.8654861111,57.5071111111,457.2 -5.8640333333,57.50760555560001,457.2 -5.8626361111,57.5101666667,457.2 -5.8615805556,57.514425,457.2 -5.8604861111,57.5167083333,457.2 -5.8572277778,57.520675,457.2 -5.855633333299999,57.5229694444,457.2 -5.8530027778,57.5265583333,457.2 -5.8536611111,57.5312138889,457.2 -5.853575,57.5335555556,457.2 -5.8515055556,57.53928333330001,457.2 -5.8521333333,57.54205,457.2 -5.8519972222,57.54394444439999,457.2 -5.8527805556,57.5497638889,457.2 -5.8457,57.5524083333,457.2 -5.8444638889,57.5549638889,457.2 -5.8476583333,57.5582833333,457.2 -5.8486388889,57.56122222219999,457.2 -5.8474555556,57.56269722219999,457.2 -5.844719444399999,57.56215,457.2 -5.8395916667,57.5595194444,457.2 -5.837630555599999,57.5567916667,457.2 -5.8345305556,57.5591333333,457.2 -5.8343666667,57.5607555556,457.2 -5.8356972222,57.5638638889,457.2 -5.8353916667,57.56890833329999,457.2 -5.8387138889,57.5702444444,457.2 -5.8395444444,57.5733666667,457.2 -5.841044444399999,57.5764694444,457.2 -5.8387083333,57.57654166670001,457.2 -5.8361222222,57.57742777779999,457.2 -5.8333333333,57.5791666667,457.2 -5.8333333333,57.6333333333,457.2 -5.9666666667,57.6333333333,457.2 -5.9666666667,57.5833333333,457.2 -5.9656777778,57.58196388890001,457.2 -5.9642555556,57.5796722222,457.2 -5.960025,57.5807944444,457.2 -5.959869444399999,57.5793611111,457.2 -5.9559944444,57.57912222219999,457.2 -5.9558777778,57.5780472222,457.2 -5.9564777778,57.57586944440001,457.2 -5.9558805556,57.57346111109999,457.2 -5.956099999999999,57.5693166667,457.2 -5.9538444444,57.5685777778,457.2 -5.9538555556,57.5656111111,457.2 -5.9564277778,57.5646305556,457.2 -5.9579111111,57.562875,457.2 -5.956577777800001,57.5613888889,457.2 -5.957716666700001,57.55955277779999,457.2 -5.9601694444,57.55749722220001,457.2 -5.9604083333,57.55506388889999,457.2 -5.9609583333,57.5524388889,457.2 -5.9635583333,57.5517277778,457.2 -5.9653055556,57.5493333333,457.2 -5.9653555556,57.546725,457.2 -5.9635722222,57.5441722222,457.2 -5.9645444444,57.5423444444,457.2 -5.9657694444,57.5413166667,457.2 -5.9664888889,57.5386861111,457.2 -5.9691638889,57.5371611111,457.2 -5.968675000000001,57.5342111111,457.2 -5.9699222222,57.53183333330001,457.2 -5.972283333299999,57.5305,457.2 -5.970030555599999,57.5282333333,457.2 -5.968847222199999,57.5265611111,457.2 -5.9705138889,57.5249805556,457.2 -5.972386111100001,57.5237527778,457.2 -5.9724361111,57.5226694444,457.2 -5.971555555599999,57.5207194444,457.2 -5.9743277778,57.5185638889,457.2 -5.9744472222,57.51658333329999,457.2 -5.975652777800001,57.515375,457.2 -5.975877777800001,57.51285,457.2 -5.976505555599999,57.5109416667,457.2 -5.9816888889,57.5094305556,457.2 -5.985802777800001,57.50885,457.2 -5.9897583333,57.5053083333,457.2 -5.9887194444,57.5034527778,457.2 -5.9866527778,57.5028861111,457.2 -5.9850777778,57.5006888889,457.2 -5.9834805556,57.4998388889,457.2 -5.983375,57.497325,457.2 -5.980113888899999,57.49499999999999,457.2 -5.9782555556,57.4932611111,457.2 -5.9807222222,57.4913833333,457.2 -5.9810944444,57.4902027778,457.2 -5.9808805556,57.4882305556,457.2 -5.9821027778,57.485675,457.2 -5.983152777799999,57.48456388889999,457.2 -5.983172222200001,57.4816833333,457.2 -5.983788888899999,57.4796861111,457.2 -5.9864222222,57.4778055556,457.2 -5.9860888889,57.4762861111,457.2 -5.987175,57.4740027778,457.2 -5.990150000000001,57.4706722222,457.2 -5.9904444444,57.468775,457.2 -5.9925472222,57.46511111109999,457.2 -5.9954416667,57.4610611111,457.2 -5.9973111111,57.4583055556,457.2 -5.999336111099999,57.45698055559999,457.2 -5.9996277778,57.4550833333,457.2 -6.0013388889,57.45395000000001,457.2 -6.0022861111,57.4519416667,457.2 -6.004125000000001,57.4504444444,457.2 -6.0071361111,57.4505277778,457.2 -6.009052777800001,57.4497472222,457.2 -6.0092,57.4480333333,457.2 -6.0119472222,57.4472277778,457.2 -6.0136555556,57.4445638889,457.2 -6.02005,57.44355277780001,457.2 -6.0248194444,57.4414222222,457.2 -6.0272611111,57.4378361111,457.2 -6.0312361111,57.43456111110001,457.2 -6.0318694444,57.4327416667,457.2 -6.0310027778,57.4279138889,457.2 -6.0259861111,57.4232166667,457.2 -6.0235111111,57.41888888890001,457.2 -6.022061111100001,57.4163277778,457.2 -6.020047222200001,57.41162777779999,457.2 -6.0197805556,57.4092083333,457.2 -6.0189972222,57.40662499999999,457.2 -6.01925,57.4043666667,457.2 -6.0186805556,57.40070000000001,457.2 -6.0175166667,57.39767777779999,457.2 -6.0179166667,57.3952388889,457.2 -6.0181277778,57.3895638889,457.2 -6.01465,57.3851805556,457.2 -6.0129305556,57.3831666667,457.2 -6.010194444399999,57.3794777778,457.2 -6.0056472222,57.3759333333,457.2 -6.002922222199999,57.3738638889,457.2 -6.001108333300001,57.3709527778,457.2 -5.997458333299999,57.3695388889,457.2 -5.994930555600001,57.3707888889,457.2 -5.9935638889,57.37047222219999,457.2 -5.9927944444,57.3679805556,457.2 -5.9930555556,57.3666666667,457.2 -5.824166666699999,57.3666666667,457.2 + + + + +
+ + EGD712A NORTHERN COMPLEX + 585202N 0052659W -
581310N 0052344W -
581920N 0055243W -
584432N 0055510W -
585202N 0052659W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,20116.8 -5.9194527778,58.7421972222,20116.8 -5.8786277778,58.3221666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.9194527778,58.7421972222,7467.6 -5.9194527778,58.7421972222,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.9194527778,58.7421972222,7467.6 -5.8786277778,58.3221666667,7467.6 -5.8786277778,58.3221666667,20116.8 -5.9194527778,58.7421972222,20116.8 -5.9194527778,58.7421972222,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.8786277778,58.3221666667,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.8786277778,58.3221666667,20116.8 -5.8786277778,58.3221666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3955861111,58.2194277778,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + +
+ + EGD712B NORTHERN COMPLEX + 591444N 0035801W -
590716N 0033308W -
580412N 0044247W -
581310N 0052344W -
585202N 0052659W -
591444N 0035801W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,20116.8 -5.4496722222,58.8673305556,20116.8 -5.3955861111,58.2194277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.9668944444,59.2454388889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.9668944444,59.2454388889,7467.6 -5.4496722222,58.8673305556,7467.6 -5.4496722222,58.8673305556,20116.8 -3.9668944444,59.2454388889,20116.8 -3.9668944444,59.2454388889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.4496722222,58.8673305556,7467.6 -5.3955861111,58.2194277778,7467.6 -5.3955861111,58.2194277778,20116.8 -5.4496722222,58.8673305556,20116.8 -5.4496722222,58.8673305556,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3955861111,58.2194277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -5.3955861111,58.2194277778,20116.8 -5.3955861111,58.2194277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -4.7129333333,58.0700666667,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -3.9668944444,59.2454388889,7467.6 -3.9668944444,59.2454388889,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + +
+ + EGD712C NORTHERN COMPLEX + 590716N 0033308W -
584654N 0022720W -
574827N 0033350W -
580412N 0044247W -
590716N 0033308W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,20116.8 -4.7129333333,58.0700666667,20116.8 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -3.552325,59.1212277778,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.552325,59.1212277778,7467.6 -4.7129333333,58.0700666667,7467.6 -4.7129333333,58.0700666667,20116.8 -3.552325,59.1212277778,20116.8 -3.552325,59.1212277778,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -4.7129333333,58.0700666667,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -4.7129333333,58.0700666667,20116.8 -4.7129333333,58.0700666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.5638888889,57.8074444444,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.552325,59.1212277778,7467.6 -3.552325,59.1212277778,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + +
+ + EGD712D NORTHERN COMPLEX + 584654N 0022720W -
583622N 0015427W -
574000N 0020624W following the line of latitude to -
574000N 0025821W -
574827N 0033350W -
584654N 0022720W
Upper limit: FL660
Lower limit: FL245
Class: AMC - Manageable.

Activity: High Energy Manoeuvres.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,20116.8 -3.5638888889,57.8074444444,20116.8 -2.972480555599999,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.1065472222,57.6666666667,20116.8 -1.907375,58.6059777778,20116.8 -2.4555083333,58.7817138889,20116.8 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -2.972480555599999,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4555083333,58.7817138889,7467.6 -3.5638888889,57.8074444444,7467.6 -3.5638888889,57.8074444444,20116.8 -2.4555083333,58.7817138889,20116.8 -2.4555083333,58.7817138889,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -3.5638888889,57.8074444444,7467.6 -2.972480555599999,57.6666666667,7467.6 -2.972480555599999,57.6666666667,20116.8 -3.5638888889,57.8074444444,20116.8 -3.5638888889,57.8074444444,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.972480555599999,57.6666666667,7467.6 -2.8281583333,57.6666666667,7467.6 -2.8281583333,57.6666666667,20116.8 -2.972480555599999,57.6666666667,20116.8 -2.972480555599999,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.8281583333,57.6666666667,7467.6 -2.6838361111,57.6666666667,7467.6 -2.6838361111,57.6666666667,20116.8 -2.8281583333,57.6666666667,20116.8 -2.8281583333,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.6838361111,57.6666666667,7467.6 -2.5395138889,57.6666666667,7467.6 -2.5395138889,57.6666666667,20116.8 -2.6838361111,57.6666666667,20116.8 -2.6838361111,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.5395138889,57.6666666667,7467.6 -2.3951916667,57.6666666667,7467.6 -2.3951916667,57.6666666667,20116.8 -2.5395138889,57.6666666667,20116.8 -2.5395138889,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.3951916667,57.6666666667,7467.6 -2.2508694444,57.6666666667,7467.6 -2.2508694444,57.6666666667,20116.8 -2.3951916667,57.6666666667,20116.8 -2.3951916667,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.2508694444,57.6666666667,7467.6 -2.1065472222,57.6666666667,7467.6 -2.1065472222,57.6666666667,20116.8 -2.2508694444,57.6666666667,20116.8 -2.2508694444,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.1065472222,57.6666666667,7467.6 -1.907375,58.6059777778,7467.6 -1.907375,58.6059777778,20116.8 -2.1065472222,57.6666666667,20116.8 -2.1065472222,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.907375,58.6059777778,7467.6 -2.4555083333,58.7817138889,7467.6 -2.4555083333,58.7817138889,20116.8 -1.907375,58.6059777778,20116.8 -1.907375,58.6059777778,7467.6 + + + + + +
+ + EGD713 FAST JET AREA SOUTH + 575900N 0065200W -
574600N 0061000W -
563500N 0052200W -
560600N 0063000W -
561000N 0065400W -
564200N 0081500W -
575000N 0081500W -
575900N 0065200W
Upper limit: FL550
Lower limit: FL245
Class: AMC: Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.

Danger Area Authority: HQ Air.

EGD713 is solely in support of Ex Joint Warrior.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,16764 -8.25,57.8333333333,16764 -8.25,56.7,16764 -6.9,56.1666666667,16764 -6.499999999999999,56.09999999999999,16764 -5.3666666667,56.5833333333,16764 -6.1666666667,57.7666666667,16764 -6.8666666667,57.9833333333,16764 + + + + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.499999999999999,56.09999999999999,7467.6 -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.8666666667,57.9833333333,7467.6 -8.25,57.8333333333,7467.6 -8.25,57.8333333333,16764 -6.8666666667,57.9833333333,16764 -6.8666666667,57.9833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -8.25,57.8333333333,7467.6 -8.25,56.7,7467.6 -8.25,56.7,16764 -8.25,57.8333333333,16764 -8.25,57.8333333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -8.25,56.7,7467.6 -6.9,56.1666666667,7467.6 -6.9,56.1666666667,16764 -8.25,56.7,16764 -8.25,56.7,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.9,56.1666666667,7467.6 -6.499999999999999,56.09999999999999,7467.6 -6.499999999999999,56.09999999999999,16764 -6.9,56.1666666667,16764 -6.9,56.1666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.499999999999999,56.09999999999999,7467.6 -5.3666666667,56.5833333333,7467.6 -5.3666666667,56.5833333333,16764 -6.499999999999999,56.09999999999999,16764 -6.499999999999999,56.09999999999999,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.3666666667,56.5833333333,7467.6 -6.1666666667,57.7666666667,7467.6 -6.1666666667,57.7666666667,16764 -5.3666666667,56.5833333333,16764 -5.3666666667,56.5833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.1666666667,57.7666666667,7467.6 -6.8666666667,57.9833333333,7467.6 -6.8666666667,57.9833333333,16764 -6.1666666667,57.7666666667,16764 -6.1666666667,57.7666666667,7467.6 + + + + + +
+ + EGD801 CAPE WRATH (NORTH WEST) + 590000N 0043000W -
584500N 0043000W following the line of latitude to -
584500N 0050000W -
590000N 0050000W following the line of latitude to -
590000N 0043000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: SI 1933/40.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5,59,16764 -4.6666666667,59,16764 -4.8333333333,59,16764 -5,59,16764 -5,58.75,16764 -4.8333333333,58.75,16764 -4.6666666667,58.75,16764 -4.5,58.75,16764 -4.5,59,16764 + + + + +
+ + EGD802 CAPE WRATH (SOUTH EAST) + 584500N 0043000W -
583435N 0043000W - then along the coastline to
583200N 0044728W -
583200N 0050000W -
584500N 0050000W -
584500N 0043000W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Remarks: SI 1933/40.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5,58.75,16764 -5,58.75,16764 -5,58.5333333333,16764 -4.7911111111,58.5333333333,16764 -4.7888388889,58.5339416667,16764 -4.7865,58.53695833330001,16764 -4.7850277778,58.5378888889,16764 -4.7821583333,58.53858055559999,16764 -4.7800055556,58.54177222220001,16764 -4.7775861111,58.54595833330001,16764 -4.7768333333,58.5516388889,16764 -4.7810527778,58.5528055556,16764 -4.7883194444,58.5533666667,16764 -4.7911638889,58.5545611111,16764 -4.7964083333,58.5577722222,16764 -4.7979111111,58.5593583333,16764 -4.8025111111,58.5609666667,16764 -4.8052416667,58.56288333330001,16764 -4.8051638889,58.5640527778,16764 -4.8023027778,58.5669916667,16764 -4.7998861111,58.5690222222,16764 -4.7968361111,58.57178333329999,16764 -4.7967944444,58.57340277780001,16764 -4.7955055556,58.57666666669999,16764 -4.7934305556,58.5765305556,16764 -4.7921222222,58.5773694444,16764 -4.7896722222,58.5768833333,16764 -4.7874611111,58.5772,16764 -4.7850138889,58.5767138889,16764 -4.7835194444,58.577375,16764 -4.7754583333,58.5777305556,16764 -4.7714388889,58.57691666669999,16764 -4.7660694444,58.57649444439999,16764 -4.7634555556,58.5804138889,16764 -4.7632,58.5837444444,16764 -4.7669722222,58.5857305556,16764 -4.7716444444,58.5903944444,16764 -4.7741055556,58.5910583333,16764 -4.7765527778,58.5937027778,16764 -4.7847944444,58.5955916667,16764 -4.7883027778,58.5985694444,16764 -4.7902638889,58.5994277778,16764 -4.7905138889,58.6004083333,16764 -4.7868416667,58.5996805556,16764 -4.7832805556,58.6003861111,16764 -4.7772444444,58.6002472222,16764 -4.7743861111,58.603275,16764 -4.7684472222,58.6043916667,16764 -4.7687055556,58.6033083333,16764 -4.7699444444,58.601575,16764 -4.7695083333,58.6004138889,16764 -4.7655805556,58.5986111111,16764 -4.7646277778,58.5974638889,16764 -4.7666861111,58.5951722222,16764 -4.7654555556,58.5926833333,16764 -4.7653222222,58.5909777778,16764 -4.7623583333,58.5883472222,16764 -4.7578777778,58.5882638889,16764 -4.7567666667,58.5894555556,16764 -4.7544055556,58.5878888889,16764 -4.7537694444,58.586375,16764 -4.7526916667,58.5836111111,16764 -4.7491583333,58.5824277778,16764 -4.7442472222,58.5834333333,16764 -4.741725,58.58420555560001,16764 -4.7414416667,58.58277222219999,16764 -4.7396111111,58.58137500000001,16764 -4.7406972222,58.5776666667,16764 -4.7425333333,58.5747527778,16764 -4.7409388889,58.5741583333,16764 -4.7406472222,58.5726361111,16764 -4.7386916667,58.5696222222,16764 -4.7324305556,58.5665194444,16764 -4.729175,58.5666777778,16764 -4.7267027778,58.5680805556,16764 -4.7254333333,58.56945555559999,16764 -4.7205027778,58.5701888889,16764 -4.7173277778,58.56917777779999,16764 -4.7176888889,58.5671916667,16764 -4.7182972222,58.5639444444,16764 -4.7163972222,58.56605,16764 -4.7141944444,58.56870277780001,16764 -4.7092666667,58.5672805556,16764 -4.7046722222,58.5656694444,16764 -4.70695,58.5640027778,16764 -4.7093138889,58.5634138889,16764 -4.7096194444,58.5607111111,16764 -4.704125,58.5585805556,16764 -4.7022972222,58.55718333330001,16764 -4.6996666667,58.5565194444,16764 -4.6955333333,58.556425,16764 -4.6915916667,58.55659722219999,16764 -4.6897777778,58.5553777778,16764 -4.6859944444,58.5553666667,16764 -4.6826361111,58.5541805556,16764 -4.6787833333,58.5532722222,16764 -4.6781583333,58.5518472222,16764 -4.6789222222,58.5505722222,16764 -4.6741638889,58.54905555560001,16764 -4.6741,58.5504944444,16764 -4.6698444444,58.55103055559999,16764 -4.6644805556,58.5506027778,16764 -4.6621944444,58.5521777778,16764 -4.6593666667,58.55115833329999,16764 -4.65495,58.5518805556,16764 -4.6533166667,58.5507444444,16764 -4.6577416667,58.5478666667,16764 -4.6579833333,58.54651388889999,16764 -4.6575111111,58.54481666670001,16764 -4.6549027778,58.54442222219999,16764 -4.6536194444,58.5433694444,16764 -4.6541222222,58.5409333333,16764 -4.6516722222,58.54035555559999,16764 -4.6519083333,58.5389111111,16764 -4.6504388889,58.5376833333,16764 -4.6507305556,58.5347111111,16764 -4.6525638889,58.5339555556,16764 -4.6531222222,58.53223611109999,16764 -4.6598416667,58.5279638889,16764 -4.6617027778,58.5253194444,16764 -4.6653138889,58.5253333333,16764 -4.6672888889,58.5264611111,16764 -4.6697861111,58.5254222222,16764 -4.6733083333,58.52202222219999,16764 -4.6764222222,58.5200694444,16764 -4.6799694444,58.5170305556,16764 -4.6825277778,58.51455,16764 -4.6842916667,58.51289722220001,16764 -4.6871722222,58.5123861111,16764 -4.6932972222,58.5093833333,16764 -4.6931583333,58.5053416667,16764 -4.6987944444,58.5027055556,16764 -4.7025694444,58.5004694444,16764 -4.7072583333,58.4989333333,16764 -4.7100555556,58.49734722219999,16764 -4.7121166667,58.4951472222,16764 -4.7145194444,58.4906916667,16764 -4.7170527778,58.4879416667,16764 -4.71765,58.48676111110001,16764 -4.7203805556,58.4843666667,16764 -4.7222277778,58.4816333333,16764 -4.7251944444,58.4800416667,16764 -4.7267472222,58.4779416667,16764 -4.7280861111,58.4753055556,16764 -4.7307222222,58.4739027778,16764 -4.7344666667,58.4713055556,16764 -4.7383333333,58.4680777778,16764 -4.7385833333,58.46690555560001,16764 -4.7443222222,58.4628361111,16764 -4.7441861111,58.4611055556,16764 -4.7425361111,58.45819166670001,16764 -4.7486472222,58.45958888889999,16764 -4.7506277778,58.45640277779999,16764 -4.7488222222,58.453025,16764 -4.7537166667,58.4507194444,16764 -4.7582972222,58.4492277778,16764 -4.7553166667,58.44839166669999,16764 -4.7476916667,58.4495444444,16764 -4.7484138889,58.4478222222,16764 -4.7491083333,58.4457388889,16764 -4.7467416667,58.44615,16764 -4.7428833333,58.4472222222,16764 -4.7409277778,58.4485222222,16764 -4.7356666667,58.4470166667,16764 -4.7324972222,58.4481611111,16764 -4.7285888889,58.45300833329999,16764 -4.7243194444,58.4576833333,16764 -4.7244527778,58.4593861111,16764 -4.7213472222,58.4635861111,16764 -4.7148,58.4631861111,16764 -4.7119722222,58.464325,16764 -4.7069027778,58.4653305556,16764 -4.7046027778,58.4666388889,16764 -4.6980888889,58.4689305556,16764 -4.694775,58.4726861111,16764 -4.6944527778,58.4752083333,16764 -4.6932833333,58.47783888890001,16764 -4.6876361111,58.4780472222,16764 -4.6836555556,58.47759166670001,16764 -4.6808611111,58.4791777778,16764 -4.6776333333,58.4818527778,16764 -4.6717666667,58.4836805556,16764 -4.6679,58.4825055556,16764 -4.6630916667,58.482425,16764 -4.661025,58.484625,16764 -4.6605111111,58.4868805556,16764 -4.6614888889,58.490725,16764 -4.6605,58.4935305556,16764 -4.660675,58.4958638889,16764 -4.6616055556,58.4968333333,16764 -4.6608916667,58.4987361111,16764 -4.6589833333,58.503,16764 -4.6583972222,58.5066055556,16764 -4.6556472222,58.5088194444,16764 -4.6511444444,58.5106194444,16764 -4.6507194444,58.5117972222,16764 -4.6481305556,58.51391666670001,16764 -4.6474027778,58.51563888890001,16764 -4.6442583333,58.5172333333,16764 -4.6433722222,58.5191388889,16764 -4.6405694444,58.5207222222,16764 -4.6376222222,58.5203333333,16764 -4.6324277778,58.5198111111,16764 -4.6274388889,58.52198055560001,16764 -4.6224472222,58.52415,16764 -4.6163972222,58.5236444444,16764 -4.6169472222,58.52183611110001,16764 -4.6151722222,58.5210638889,16764 -4.6144638889,58.5184722222,16764 -4.6153722222,58.51683611110001,16764 -4.6153833333,58.5146777778,16764 -4.6192472222,58.5135222222,16764 -4.6205527778,58.51259722220001,16764 -4.6184944444,58.5073277778,16764 -4.61745,58.50780833329999,16764 -4.6179666667,58.5101333333,16764 -4.6177833333,58.51229444440001,16764 -4.6135638889,58.5132777778,16764 -4.6115083333,58.51565555559999,16764 -4.6108388889,58.52052222219999,16764 -4.6076555556,58.5239138889,16764 -4.6025166667,58.52644444439999,16764 -4.5996138889,58.52668055560001,16764 -4.59945,58.5291111111,16764 -4.5989638889,58.5318166667,16764 -4.5949833333,58.5337833333,16764 -4.5909666667,58.5352138889,16764 -4.59195,58.5369,16764 -4.5906833333,58.5407,16764 -4.591675,58.54481388890001,16764 -4.5941777778,58.54845,16764 -4.6008472222,58.5526277778,16764 -4.6020444444,58.55485,16764 -4.5994,58.5585861111,16764 -4.594725,58.5604805556,16764 -4.5946861111,58.5622777778,16764 -4.5930805556,58.5638361111,16764 -4.5935638889,58.5657138889,16764 -4.5960277778,58.566475,16764 -4.594225,58.56767777779999,16764 -4.597375,58.5684222222,16764 -4.5973111111,58.5698638889,16764 -4.5962222222,58.5714111111,16764 -4.5939083333,58.5727166667,16764 -4.5908972222,58.5738555556,16764 -4.5868611111,58.5751055556,16764 -4.5901583333,58.5754888889,16764 -4.58805,58.5772388889,16764 -4.5841194444,58.5775861111,16764 -4.5809138889,58.5784611111,16764 -4.5794527778,58.5796583333,16764 -4.5767638889,58.5805194444,16764 -4.5751444444,58.57956388889999,16764 -4.570575,58.5758833333,16764 -4.5684527778,58.5751166667,16764 -4.5652805556,58.5764361111,16764 -4.561925,58.5775833333,16764 -4.55375,58.5763972222,16764 -4.5515166667,58.57644166670001,16764 -4.5434027778,58.57840000000001,16764 -4.5442333333,58.5803611111,16764 -4.5396555556,58.5789222222,16764 -4.53655,58.5788055556,16764 -4.5354166667,58.5798166667,16764 -4.5332722222,58.5786888889,16764 -4.5269027778,58.57863611110001,16764 -4.5256972222,58.5762333333,16764 -4.5235944444,58.5757361111,16764 -4.52175,58.5764,16764 -4.5173805556,58.5778333333,16764 -4.5143138889,58.5782527778,16764 -4.51075,58.576525,16764 -4.506925,58.5759722222,16764 -4.5025916667,58.5755166667,16764 -4.5,58.57638888890001,16764 -4.5,58.75,16764 + + + + +
+ + EGD803 GARVIE ISLAND + A circle, 4 NM radius, centred at 583705N 0045220W
Upper limit: 40000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS) / High Energy Manoeuvres / Electronic/Optical Hazards.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Pre-flight information / Booking: Range Control, Tel: 01971-511242 when open; at other times Tain Range ATC, Tel: 01862-892185 Ext 4945.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8722222222,58.6845611849,12192 -4.8815454206,58.6843834303,12192 -4.8908185925,58.6838511206,12192 -4.8999919843,58.6829671118,12192 -4.909016387,58.6817361468,12192 -4.9178434039,58.6801648294,12192 -4.9264257149,58.6782615883,12192 -4.9347173328,58.6760366312,12192 -4.9426738539,58.67350188899999,12192 -4.9502526977,58.67067095120001,12192 -4.9574133368,58.66755899179999,12192 -4.9641175159,58.66418268660001,12192 -4.9703294558,58.66056012310001,12192 -4.9760160454,58.6567107024,12192 -4.981147017,58.6526550338,12192 -4.9856951069,58.6484148234,12192 -4.9896361975,58.6440127571,12192 -4.9929494437,58.6394723782,12192 -4.9956173795,58.63481796029999,12192 -4.9976260072,58.6300743768,12192 -4.9989648664,58.6252669678,12192 -4.9996270849,58.62042140359999,12192 -4.9996094092,58.6155635479,12192 -4.9989122161,58.610719319,12192 -4.9975395044,58.6059145521,12192 -4.9954988679,58.6011748612,12192 -4.992801449,58.59652550329999,12192 -4.9894618741,58.5919912442,12192 -4.98549817,58.58759622699999,12192 -4.9809316641,58.58336384460001,12192 -4.9757868662,58.57931661620001,12192 -4.9700913349,58.57547606800001,12192 -4.9638755284,58.5718626203,12192 -4.9571726403,58.5684954797,12192 -4.9500184221,58.56539253839999,12192 -4.9424509926,58.5625702802,12192 -4.9345106356,58.560043694,12192 -4.9262395872,58.5578261953,12192 -4.9176818128,58.55592955629999,12192 -4.9088827764,58.55436384389999,12192 -4.8998892021,58.5531373672,12192 -4.8907488293,58.5522566345,12192 -4.8815101633,58.5517263187,12192 -4.8722222222,58.5515492336,12192 -4.8629342812,58.5517263187,12192 -4.8536956152,58.5522566345,12192 -4.8445552423,58.5531373672,12192 -4.835561668,58.55436384389999,12192 -4.8267626317,58.55592955629999,12192 -4.8182048573,58.5578261953,12192 -4.8099338088,58.560043694,12192 -4.8019934519,58.5625702802,12192 -4.7944260223,58.56539253839999,12192 -4.7872718041,58.5684954797,12192 -4.780568916,58.5718626203,12192 -4.7743531095,58.57547606800001,12192 -4.7686575783,58.57931661620001,12192 -4.7635127804,58.58336384460001,12192 -4.7589462744,58.58759622699999,12192 -4.7549825704,58.5919912442,12192 -4.7516429954,58.59652550329999,12192 -4.7489455766,58.6011748612,12192 -4.7469049401,58.6059145521,12192 -4.7455322283,58.610719319,12192 -4.7448350352,58.6155635479,12192 -4.7448173595,58.62042140359999,12192 -4.745479578,58.6252669678,12192 -4.7468184373,58.6300743768,12192 -4.7488270649,58.63481796029999,12192 -4.7514950008,58.6394723782,12192 -4.7548082469,58.6440127571,12192 -4.7587493376,58.6484148234,12192 -4.7632974274,58.6526550338,12192 -4.7684283991,58.6567107024,12192 -4.7741149886,58.66056012310001,12192 -4.7803269286,58.66418268660001,12192 -4.7870311076,58.66755899179999,12192 -4.7941917468,58.67067095120001,12192 -4.8017705905,58.67350188899999,12192 -4.8097271116,58.6760366312,12192 -4.8180187296,58.6782615883,12192 -4.8266010405,58.6801648294,12192 -4.8354280575,58.6817361468,12192 -4.8444524601,58.6829671118,12192 -4.853625852,58.6838511206,12192 -4.8628990238,58.6843834303,12192 -4.8722222222,58.6845611849,12192 + + + + +
+ + EGD809C MORAY FIRTH (CENTRAL) + 585000N 0023314W following the line of latitude to -
585000N 0014526W -
582600N 0015049W following the line of latitude to -
582600N 0024048W -
585000N 0023314W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5538888889,58.8333333333,16764 -2.68,58.4333333333,16764 -2.5133888889,58.4333333333,16764 -2.3467777778,58.4333333333,16764 -2.1801666667,58.4333333333,16764 -2.0135555556,58.4333333333,16764 -1.8469444444,58.4333333333,16764 -1.7572222222,58.8333333333,16764 -1.9165555556,58.8333333333,16764 -2.0758888889,58.8333333333,16764 -2.2352222222,58.8333333333,16764 -2.3945555556,58.8333333333,16764 -2.5538888889,58.8333333333,16764 + + + + +
+ + EGD809N MORAY FIRTH (NORTH) + 592300N 0015130W following the line of latitude to -
592300N 0014200W -
590500N 0014200W -
585000N 0014526W following the line of latitude to -
585000N 0023314W -
585800N 0023040W -
592300N 0015130W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8583333333,59.3833333333,16764 -2.5111111111,58.9666666667,16764 -2.5538888889,58.8333333333,16764 -2.3945555556,58.8333333333,16764 -2.2352222222,58.8333333333,16764 -2.0758888889,58.8333333333,16764 -1.9165555556,58.8333333333,16764 -1.7572222222,58.8333333333,16764 -1.7,59.0833333333,16764 -1.7,59.3833333333,16764 -1.8583333333,59.3833333333,16764 + + + + +
+ + EGD809S MORAY FIRTH (SOUTH) + 582600N 0024048W following the line of latitude to -
582600N 0015049W -
575000N 0015840W following the line of latitude to -
575000N 0022415W -
581630N 0024345W -
582600N 0024048W
Upper limit: 55000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft system (VLOS/BVLOS) / High Energy Manoeuvres.

Service: SUAAIS: Scottish Information on 133.675 MHz.

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel: 01489-612495.

Danger Area Authority: HQ Air.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.68,58.4333333333,16764 -2.7291666667,58.275,16764 -2.4041666667,57.8333333333,16764 -2.262037037,57.8333333333,16764 -2.1199074074,57.8333333333,16764 -1.9777777778,57.8333333333,16764 -1.8469444444,58.4333333333,16764 -2.0135555556,58.4333333333,16764 -2.1801666667,58.4333333333,16764 -2.3467777778,58.4333333333,16764 -2.5133888889,58.4333333333,16764 -2.68,58.4333333333,16764 + + + + +
+ + EGD901 FAST JET AREA NORTH + 594000N 0013000W -
591000N 0010000W -
580215N 0000948E -
574700N 0010000W -
574000N 0013100W following the line of latitude to -
574000N 0025821W -
581920N 0055243W -
595000N 0060149W -
594000N 0013000W
Upper limit: FL550
Lower limit: FL245
Class: AMC: Manageable.

Activity: High Energy Manoeuvres / Ordnance, Munitions & Explosives (OME).

Contact: Booking: Military Airspace Management Cell – Managed Airspace, Tel 01489-612495.

Danger Area Authority: HQ Air.

EGD901 is solely in support of Ex Joint Warrior.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,16764 -6.030277777799999,59.8333333333,16764 -5.878611111100001,58.3222222222,16764 -2.9725,57.6666666667,16764 -2.8107407407,57.6666666667,16764 -2.6489814815,57.6666666667,16764 -2.4872222222,57.6666666667,16764 -2.325462963,57.6666666667,16764 -2.1637037037,57.6666666667,16764 -2.0019444444,57.6666666667,16764 -1.8401851852,57.6666666667,16764 -1.6784259259,57.6666666667,16764 -1.5166666667,57.6666666667,16764 -1,57.7833333333,16764 0.1633333333,58.0375,16764 -1,59.1666666667,16764 -1.5,59.6666666667,16764 + + + + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,7467.6 -6.030277777799999,59.8333333333,7467.6 -5.878611111100001,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 -1,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.5,59.6666666667,7467.6 -6.030277777799999,59.8333333333,7467.6 -6.030277777799999,59.8333333333,16764 -1.5,59.6666666667,16764 -1.5,59.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -6.030277777799999,59.8333333333,7467.6 -5.878611111100001,58.3222222222,7467.6 -5.878611111100001,58.3222222222,16764 -6.030277777799999,59.8333333333,16764 -6.030277777799999,59.8333333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -5.878611111100001,58.3222222222,7467.6 -2.9725,57.6666666667,7467.6 -2.9725,57.6666666667,16764 -5.878611111100001,58.3222222222,16764 -5.878611111100001,58.3222222222,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.9725,57.6666666667,7467.6 -2.8107407407,57.6666666667,7467.6 -2.8107407407,57.6666666667,16764 -2.9725,57.6666666667,16764 -2.9725,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.8107407407,57.6666666667,7467.6 -2.6489814815,57.6666666667,7467.6 -2.6489814815,57.6666666667,16764 -2.8107407407,57.6666666667,16764 -2.8107407407,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.6489814815,57.6666666667,7467.6 -2.4872222222,57.6666666667,7467.6 -2.4872222222,57.6666666667,16764 -2.6489814815,57.6666666667,16764 -2.6489814815,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.4872222222,57.6666666667,7467.6 -2.325462963,57.6666666667,7467.6 -2.325462963,57.6666666667,16764 -2.4872222222,57.6666666667,16764 -2.4872222222,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.325462963,57.6666666667,7467.6 -2.1637037037,57.6666666667,7467.6 -2.1637037037,57.6666666667,16764 -2.325462963,57.6666666667,16764 -2.325462963,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.1637037037,57.6666666667,7467.6 -2.0019444444,57.6666666667,7467.6 -2.0019444444,57.6666666667,16764 -2.1637037037,57.6666666667,16764 -2.1637037037,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -2.0019444444,57.6666666667,7467.6 -1.8401851852,57.6666666667,7467.6 -1.8401851852,57.6666666667,16764 -2.0019444444,57.6666666667,16764 -2.0019444444,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.8401851852,57.6666666667,7467.6 -1.6784259259,57.6666666667,7467.6 -1.6784259259,57.6666666667,16764 -1.8401851852,57.6666666667,16764 -1.8401851852,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.6784259259,57.6666666667,7467.6 -1.5166666667,57.6666666667,7467.6 -1.5166666667,57.6666666667,16764 -1.6784259259,57.6666666667,16764 -1.6784259259,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1.5166666667,57.6666666667,7467.6 -1,57.7833333333,7467.6 -1,57.7833333333,16764 -1.5166666667,57.6666666667,16764 -1.5166666667,57.6666666667,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1,57.7833333333,7467.6 0.1633333333,58.0375,7467.6 0.1633333333,58.0375,16764 -1,57.7833333333,16764 -1,57.7833333333,7467.6 + + + + + + relativeToGround + + + relativeToGround + + 0.1633333333,58.0375,7467.6 -1,59.1666666667,7467.6 -1,59.1666666667,16764 0.1633333333,58.0375,16764 0.1633333333,58.0375,7467.6 + + + + + + relativeToGround + + + relativeToGround + + -1,59.1666666667,7467.6 -1.5,59.6666666667,7467.6 -1.5,59.6666666667,16764 -1,59.1666666667,16764 -1,59.1666666667,7467.6 + + + + + +
+
+ + Prohibited + + EGP611 COULPORT / FASLANE + A circle, 2 NM radius, centred at 560331N 0045159W
Upper limit: 2200 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8663888889,56.0918776254,670.5600000000001 -4.8725074402,56.0917011577,670.5600000000001 -4.878560967,56.0911736299,670.5600000000001 -4.8844851413,56.0903006481,670.5600000000001 -4.8902170197,56.089091489,670.5600000000001 -4.8956957176,56.0875590008,670.5600000000001 -4.9008630591,56.0857194653,670.5600000000001 -4.9056641986,56.0835924241,670.5600000000001 -4.9100482046,56.0812004696,670.5600000000001 -4.9139686016,56.0785690036,670.5600000000001 -4.9173838627,56.0757259658,670.5600000000001 -4.9202578484,56.07270153620001,670.5600000000001 -4.9225601874,56.069527813,670.5600000000001 -4.9242665941,56.0662384706,670.5600000000001 -4.9253591212,56.06286840180001,670.5600000000001 -4.9258263439,56.0594533465,670.5600000000001 -4.9256634744,56.056029512,670.5600000000001 -4.9248724057,56.05263318939999,670.5600000000001 -4.9234616844,56.0493003688,670.5600000000001 -4.9214464135,56.04606635790001,670.5600000000001 -4.9188480857,56.0429654094,670.5600000000001 -4.9156943503,56.04003035829999,670.5600000000001 -4.9120187157,56.0372922762,670.5600000000001 -4.9078601907,56.0347801428,670.5600000000001 -4.9032628694,56.03252054120001,670.5600000000001 -4.8982754627,56.03053737780001,670.5600000000001 -4.8929507836,56.0288516311,670.5600000000001 -4.887345189,56.0274811305,670.5600000000001 -4.8815179867,56.02644037000001,670.5600000000001 -4.8755308106,56.0257403549,670.5600000000001 -4.8694469739,56.0253884872,670.5600000000001 -4.8633308039,56.0253884872,670.5600000000001 -4.8572469672,56.0257403549,670.5600000000001 -4.8512597911,56.02644037000001,670.5600000000001 -4.8454325887,56.0274811305,670.5600000000001 -4.8398269942,56.0288516311,670.5600000000001 -4.8345023151,56.03053737780001,670.5600000000001 -4.8295149084,56.03252054120001,670.5600000000001 -4.824917587,56.0347801428,670.5600000000001 -4.8207590621,56.0372922762,670.5600000000001 -4.8170834275,56.04003035829999,670.5600000000001 -4.8139296921,56.0429654094,670.5600000000001 -4.8113313643,56.04606635790001,670.5600000000001 -4.8093160933,56.0493003688,670.5600000000001 -4.8079053721,56.05263318939999,670.5600000000001 -4.8071143034,56.056029512,670.5600000000001 -4.8069514339,56.0594533465,670.5600000000001 -4.8074186566,56.06286840180001,670.5600000000001 -4.8085111837,56.0662384706,670.5600000000001 -4.8102175904,56.069527813,670.5600000000001 -4.8125199293,56.07270153620001,670.5600000000001 -4.8153939151,56.0757259658,670.5600000000001 -4.8188091761,56.0785690036,670.5600000000001 -4.8227295731,56.0812004696,670.5600000000001 -4.8271135792,56.0835924241,670.5600000000001 -4.8319147186,56.0857194653,670.5600000000001 -4.8370820602,56.0875590008,670.5600000000001 -4.8425607581,56.089091489,670.5600000000001 -4.8482926365,56.0903006481,670.5600000000001 -4.8542168107,56.0911736299,670.5600000000001 -4.8602703376,56.0917011577,670.5600000000001 -4.8663888889,56.0918776254,670.5600000000001 + + + + +
+ + EGP813 DOUNREAY + A circle, 2 NM radius, centred at 583435N 0034434W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.7427777778,58.609642007,640.08 -3.7493300434,58.609465595,640.08 -3.755812657199999,58.6089382341,640.08 -3.7621567139,58.6080655301,640.08 -3.7682947936,58.6068567592,640.08 -3.7741616829,58.6053247684,640.08 -3.7796950733,58.6034858381,640.08 -3.7848362261,58.60135950790001,640.08 -3.7895305989,58.5989683673,640.08 -3.7937284254,58.59633781390001,640.08 -3.7973852435,58.5934957828,640.08 -3.8004623645,58.5904724474,640.08 -3.8029272805,58.58729989820001,640.08 -3.8047540042,58.5840118007,640.08 -3.8059233382,58.58064303679999,640.08 -3.8064230716,58.5772293343,640.08 -3.8062481016,58.57380688690001,640.08 -3.805400479199999,58.57041197070001,640.08 -3.8038893795,58.5670805596,640.08 -3.8017309962,58.5638479444,640.08 -3.7989483623,58.56074835999999,640.08 -3.7955710999,58.5578146233,640.08 -3.7916351009,58.55507778770001,640.08 -3.7871821421,58.5525668152,640.08 -3.7822594409,58.5503082721,640.08 -3.7769191536,58.5483260487,640.08 -3.7712178237,58.5466411091,640.08 -3.7652157856,58.5452712702,640.08 -3.758976528799999,58.5442310155,640.08 -3.7525660311,58.5435313422,640.08 -3.7460520656,58.5431796467,640.08 -3.7395034899,58.5431796467,640.08 -3.7329895244,58.5435313422,640.08 -3.7265790268,58.5442310155,640.08 -3.720339769999999,58.5452712702,640.08 -3.7143377318,58.5466411091,640.08 -3.708636402,58.5483260487,640.08 -3.7032961146,58.5503082721,640.08 -3.6983734134,58.5525668152,640.08 -3.6939204547,58.55507778770001,640.08 -3.6899844556,58.5578146233,640.08 -3.6866071933,58.56074835999999,640.08 -3.6838245594,58.5638479444,640.08 -3.681666176,58.5670805596,640.08 -3.6801550763,58.57041197070001,640.08 -3.679307454,58.57380688690001,640.08 -3.679132483900001,58.5772293343,640.08 -3.6796322173,58.58064303679999,640.08 -3.6808015513,58.5840118007,640.08 -3.682628275,58.58729989820001,640.08 -3.6850931911,58.5904724474,640.08 -3.6881703121,58.5934957828,640.08 -3.691827130100001,58.59633781390001,640.08 -3.6960249567,58.5989683673,640.08 -3.7007193295,58.60135950790001,640.08 -3.705860482299999,58.6034858381,640.08 -3.7113938727,58.6053247684,640.08 -3.717260762,58.6068567592,640.08 -3.7233988416,58.6080655301,640.08 -3.7297428984,58.6089382341,640.08 -3.7362255122,58.609465595,640.08 -3.7427777778,58.609642007,640.08 + + + + +
+
+ + Restricted + + EGR002 DEVONPORT + A circle, 1 NM radius, centred at 502317N 0041114W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by helicopter for the purpose of landing or taking off from Kinterbury Point (KP) Helicopter Landing Site (HLS) and Ships within HM Naval Base with the permission of FOST / Plymouth Military Radar and in accordance with any conditions to which permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1872222222,50.40470473780001,609.6 -4.1910152222,50.404527252,609.6 -4.1947272975,50.4039985814,609.6 -4.1982792553,50.403130005,609.6 -4.201595329,50.4019400528,609.6 -4.2046047982,50.4004541095,609.6 -4.2072435002,50.3987038712,609.6 -4.2094551986,50.3967266679,609.6 -4.2111927823,50.3945646657,609.6 -4.2124192668,50.3922639654,609.6 -4.2131085786,50.38987361900001,609.6 -4.2132461049,50.38744458189999,609.6 -4.2128289986,50.38502862690001,609.6 -4.211866232,50.38267724,609.6 -4.2103783981,50.3804405238,609.6 -4.2083972659,50.3783661309,609.6 -4.2059650983,50.37649824940001,609.6 -4.203133748,50.3748766639,609.6 -4.1999635509,50.373535909,609.6 -4.1965220414,50.372504536,609.6 -4.1928825154,50.3718045064,609.6 -4.1891224728,50.3714507253,609.6 -4.1853219717,50.3714507253,609.6 -4.1815619291,50.3718045064,609.6 -4.177922403,50.372504536,609.6 -4.1744808935,50.373535909,609.6 -4.1713106965,50.3748766639,609.6 -4.1684793461,50.37649824940001,609.6 -4.1660471786,50.3783661309,609.6 -4.1640660464,50.3804405238,609.6 -4.1625782125,50.38267724,609.6 -4.1616154458,50.38502862690001,609.6 -4.1611983396,50.38744458189999,609.6 -4.1613358658,50.38987361900001,609.6 -4.1620251776,50.3922639654,609.6 -4.1632516622,50.3945646657,609.6 -4.1649892459,50.3967266679,609.6 -4.1672009443,50.3987038712,609.6 -4.1698396462,50.4004541095,609.6 -4.1728491155,50.4019400528,609.6 -4.1761651891,50.403130005,609.6 -4.1797171469,50.4039985814,609.6 -4.1834292222,50.404527252,609.6 -4.1872222222,50.40470473780001,609.6 + + + + +
+ + EGR063 DUNGENESS + A circle, 2 NM radius, centred at 505449N 0005717E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Dungeness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight permitted by an aircraft which has taken off from or intends to land at London Ashford (Lydd) Airport flying in accordance with normal aviation practice which remains at least 1.5 NM from the position given at column 1 for Dungeness.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9547222222,50.9469064086,609.6 0.9493030469999999,50.9467298142,609.6 0.9439414384,50.9462019069,609.6 0.9386943478000001,50.9453282944,609.6 0.9336175023,50.944118256,609.6 0.9287648099,50.9425846441,609.6 0.9241877838000001,50.9407437458,609.6 0.9199349934999999,50.9386151102,609.6 0.9160515477,50.93622133869999,609.6 0.9125786149000001,50.9335878442,609.6 0.9095529867,50.9307425803,609.6 0.9070066892999999,50.92771574309999,609.6 0.9049666453,50.9245394495,609.6 0.9034543918999999,50.921247396,609.6 0.9024858558000001,50.9178744997,609.6 0.9020711889,50.9144565275,609.6 0.9022146659,50.91102971669999,609.6 0.9029146436,50.9076303902,609.6 0.9041635837000001,50.904294572,609.6 0.9059481377999999,50.9010576053,609.6 0.9082492934999999,50.89795377900001,609.6 0.9110425797,50.8950159648,609.6 0.9142983296,50.89227527039999,609.6 0.9179819975,50.8897607111,609.6 0.9220545264000001,50.8874989035,609.6 0.9264727623,50.8855137854,609.6 0.9311899111,50.8838263633,609.6 0.9361560329,50.8824544915,609.6 0.9413185687,50.881412684,609.6 0.9466228938999999,50.88071196209999,609.6 0.9520128933000001,50.8803597382,609.6 0.9574315511999999,50.8803597382,609.6 0.9628215505999999,50.88071196209999,609.6 0.9681258757,50.881412684,609.6 0.9732884115000001,50.8824544915,609.6 0.9782545333,50.8838263633,609.6 0.9829716822,50.8855137854,609.6 0.9873899180999999,50.8874989035,609.6 0.9914624469,50.8897607111,609.6 0.9951461149000002,50.89227527039999,609.6 0.9984018648,50.8950159648,609.6 1.001195151,50.89795377900001,609.6 1.0034963066,50.9010576053,609.6 1.0052808608,50.904294572,609.6 1.0065298009,50.9076303902,609.6 1.0072297785,50.91102971669999,609.6 1.0073732555,50.9144565275,609.6 1.0069585887,50.9178744997,609.6 1.0059900525,50.921247396,609.6 1.0044777991,50.9245394495,609.6 1.0024377552,50.92771574309999,609.6 0.9998914577,50.9307425803,609.6 0.9968658296,50.9335878442,609.6 0.9933928967,50.93622133869999,609.6 0.9895094509000001,50.9386151102,609.6 0.9852566606999998,50.9407437458,609.6 0.9806796346,50.9425846441,609.6 0.9758269422,50.944118256,609.6 0.9707500967,50.9453282944,609.6 0.9655030060000001,50.9462019069,609.6 0.9601413974,50.9467298142,609.6 0.9547222222,50.9469064086,609.6 + + + + +
+ + EGR095 SARK + A circle, 3 NM radius, centred at 492546N 0022145W
Upper limit: 2374 FT MSL
Lower limit: SFC
Class: Flight is not permitted except in conformity with any permission granted by or on behalf of the Channel Islands Director of Civil Aviation. The Island of Sark is within Bailiwick of Guernsey territorial waters although within the Brest FIR.

Guernsey SI 1985/21.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3625,49.4794001476,723.5952000000001 -2.3689155084,49.4792247688,723.5952000000001 -2.3752858801,49.4786998665,723.5952000000001 -2.3815662987,49.4778291334,723.5952000000001 -2.3877125865,49.4766186951,723.5952000000001 -2.3936815175,49.4750770665,723.5952000000001 -2.3994311242,49.4732150914,723.5952000000001 -2.4049209946,49.4710458655,723.5952000000001 -2.410112558,49.46858464350001,723.5952000000001 -2.414969357,49.4658487315,723.5952000000001 -2.4194573051,49.4628573634,723.5952000000001 -2.4235449258,49.4596315661,723.5952000000001 -2.4272035732,49.4561940094,723.5952000000001 -2.4304076327,49.45256884679999,723.5952000000001 -2.4331346987,49.4487815446,723.5952000000001 -2.4353657305,49.4448587019,723.5952000000001 -2.4370851827,49.4408278634,723.5952000000001 -2.4382811118,49.43671732549999,723.5952000000001 -2.4389452565,49.4325559366,723.5952000000001 -2.439073092,49.4283728951,723.5952000000001 -2.4386638582,49.42419754379999,723.5952000000001 -2.437720561,49.420059164,723.5952000000001 -2.4362499477,49.41598677069999,723.5952000000001 -2.4342624555,49.41200890900001,723.5952000000001 -2.4317721356,49.4081534549,723.5952000000001 -2.4287965508,49.40444741980001,723.5952000000001 -2.4253566504,49.4009167627,723.5952000000001 -2.4214766204,49.3975862086,723.5952000000001 -2.4171837129,49.3944790766,723.5952000000001 -2.4125080535,49.3916171169,723.5952000000001 -2.4074824296,49.3890203603,723.5952000000001 -2.4021420611,49.3867069782,723.5952000000001 -2.3965243537,49.3846931567,723.5952000000001 -2.3906686384,49.382992984,723.5952000000001 -2.3846158977,49.3816183531,723.5952000000001 -2.3784084803,49.3805788785,723.5952000000001 -2.3720898073,49.3798818303,723.5952000000001 -2.3657040712,49.3795320833,723.5952000000001 -2.3592959288,49.3795320833,723.5952000000001 -2.3529101927,49.3798818303,723.5952000000001 -2.3465915197,49.3805788785,723.5952000000001 -2.3403841023,49.3816183531,723.5952000000001 -2.3343313616,49.382992984,723.5952000000001 -2.3284756463,49.3846931567,723.5952000000001 -2.3228579389,49.3867069782,723.5952000000001 -2.3175175704,49.3890203603,723.5952000000001 -2.3124919465,49.3916171169,723.5952000000001 -2.3078162871,49.3944790766,723.5952000000001 -2.3035233796,49.3975862086,723.5952000000001 -2.2996433496,49.4009167627,723.5952000000001 -2.2962034492,49.40444741980001,723.5952000000001 -2.2932278644,49.4081534549,723.5952000000001 -2.2907375445,49.41200890900001,723.5952000000001 -2.2887500523,49.41598677069999,723.5952000000001 -2.287279439,49.420059164,723.5952000000001 -2.2863361418,49.42419754379999,723.5952000000001 -2.285926908,49.4283728951,723.5952000000001 -2.2860547435,49.4325559366,723.5952000000001 -2.2867188882,49.43671732549999,723.5952000000001 -2.2879148173,49.4408278634,723.5952000000001 -2.2896342695,49.4448587019,723.5952000000001 -2.2918653013,49.4487815446,723.5952000000001 -2.2945923673,49.45256884679999,723.5952000000001 -2.2977964268,49.4561940094,723.5952000000001 -2.3014550742,49.4596315661,723.5952000000001 -2.3055426949,49.4628573634,723.5952000000001 -2.310030643,49.4658487315,723.5952000000001 -2.314887442,49.46858464350001,723.5952000000001 -2.3200790054,49.4710458655,723.5952000000001 -2.3255688758,49.4732150914,723.5952000000001 -2.3313184825,49.4750770665,723.5952000000001 -2.3372874135,49.4766186951,723.5952000000001 -2.3434337013,49.4778291334,723.5952000000001 -2.3497141199,49.4786998665,723.5952000000001 -2.3560844916,49.4792247688,723.5952000000001 -2.3625,49.4794001476,723.5952000000001 + + + + +
+ + EGR101 ALDERMASTON + A circle, 1.5 NM radius, centred at 512203N 0010847W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Aldermaston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1463888889,51.3924695424,731.52 -1.1511093435,51.3922941889,731.52 -1.1557634263,51.391770594,731.52 -1.1602857032,51.3909061194,731.52 -1.164612602,51.38971291910001,731.52 -1.16868331,51.3882077678,731.52 -1.1724406312,51.3864118238,731.52 -1.1758317931,51.3843503304,731.52 -1.1788091878,51.3820522599,731.52 -1.1813310418,51.3795499048,731.52 -1.1833620001,51.376878423,731.52 -1.1848736205,51.374075342,731.52 -1.1858447687,51.3711800313,731.52 -1.1862619106,51.36823314810001,731.52 -1.1861192962,51.36527606590001,731.52 -1.1854190348,51.3623502939,731.52 -1.1841710595,51.3594968935,731.52 -1.1823929815,51.3567559032,731.52 -1.1801098382,51.3541657774,731.52 -1.177353737,51.3517628473,731.52 -1.174163402,51.3495808134,731.52 -1.1705836278,51.3476502732,731.52 -1.1666646506,51.3459982944,731.52 -1.1624614438,51.3446480361,731.52 -1.1580329486,51.34361842609999,731.52 -1.1534412499,51.342923896,731.52 -1.1487507096,51.3425741802,731.52 -1.1440270682,51.3425741802,731.52 -1.1393365279,51.342923896,731.52 -1.1347448292,51.34361842609999,731.52 -1.130316334,51.3446480361,731.52 -1.1261131272,51.3459982944,731.52 -1.12219415,51.3476502732,731.52 -1.1186143758,51.3495808134,731.52 -1.1154240407,51.3517628473,731.52 -1.1126679396,51.3541657774,731.52 -1.1103847963,51.3567559032,731.52 -1.1086067183,51.3594968935,731.52 -1.1073587429,51.3623502939,731.52 -1.1066584816,51.36527606590001,731.52 -1.1065158672,51.36823314810001,731.52 -1.106933009,51.3711800313,731.52 -1.1079041573,51.374075342,731.52 -1.1094157777,51.376878423,731.52 -1.111446736,51.3795499048,731.52 -1.1139685899,51.3820522599,731.52 -1.1169459847,51.3843503304,731.52 -1.1203371465,51.3864118238,731.52 -1.1240944678,51.3882077678,731.52 -1.1281651757,51.38971291910001,731.52 -1.1324920746,51.3909061194,731.52 -1.1370143515,51.391770594,731.52 -1.1416684343,51.3922941889,731.52 -1.1463888889,51.3924695424,731.52 + + + + +
+ + EGR104 BURGHFIELD + A circle, 1 NM radius, centred at 512424N 0010125W
Upper limit: 2400 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Burghfield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0236111111,51.42331292830001,731.52 -1.0274878214,51.4231354714,731.52 -1.0312818179,51.4226068868,731.52 -1.0349121572,51.4217384523,731.52 -1.0383013983,51.4205486955,731.52 -1.0413772588,51.4190629976,731.52 -1.0440741597,51.4173130507,731.52 -1.0463346245,51.4153361794,731.52 -1.0481105042,51.4131745437,731.52 -1.0493640011,51.4108742375,731.52 -1.0500684699,51.4084843048,731.52 -1.0502089796,51.4060556927,731.52 -1.0497826245,51.403640165,731.52 -1.0487985788,51.40128919829999,731.52 -1.0472778936,51.3990528858,731.52 -1.0452530415,51.3969788707,731.52 -1.0427672195,51.3951113324,731.52 -1.0398734246,51.39349004689999,731.52 -1.0366333234,51.3921495417,731.52 -1.033115938,51.3911183617,731.52 -1.0293961781,51.3904184636,731.52 -1.0255532497,51.3900647491,731.52 -1.0216689725,51.3900647491,731.52 -1.0178260441,51.3904184636,731.52 -1.0141062843,51.3911183617,731.52 -1.0105888988,51.3921495417,731.52 -1.0073487976,51.39349004689999,731.52 -1.0044550028,51.3951113324,731.52 -1.0019691807,51.3969788707,731.52 -0.9999443286,51.3990528858,731.52 -0.9984236434,51.40128919829999,731.52 -0.9974395977,51.403640165,731.52 -0.9970132426,51.4060556927,731.52 -0.9971537523,51.4084843048,731.52 -0.9978582211,51.4108742375,731.52 -0.999111718,51.4131745437,731.52 -1.0008875977,51.4153361794,731.52 -1.0031480625,51.4173130507,731.52 -1.0058449634,51.4190629976,731.52 -1.008920824,51.4205486955,731.52 -1.012310065,51.4217384523,731.52 -1.0159404043,51.4226068868,731.52 -1.0197344008,51.4231354714,731.52 -1.0236111111,51.42331292830001,731.52 + + + + +
+ + EGR105 HIGHGROVE HOUSE + A circle, 1.5 NM radius, centred at 513720N 0021050W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Gloucestershire Constabulary Royalty Household Protection Group;
any aircraft either operated by a member of the Royal Family, or landing in the grounds of Highgrove House at the invitation of the person in charge of the household there, provided that the Gloucestershire Constabulary Royalty Household Protection Group has been informed in advance of such intended flight or landing.

SI 907/2018.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1805555556,51.6471906741,609.6 -2.1853024165,51.6470153274,609.6 -2.1899825335,51.6464917528,609.6 -2.1945301052,51.64562731180001,609.6 -2.1988812033,51.6444341583,609.6 -2.2029746741,51.6429290662,609.6 -2.2067530014,51.6411331935,609.6 -2.2101631173,51.6390717828,609.6 -2.2131571481,51.63677380549999,609.6 -2.2156930867,51.6342715531,609.6 -2.2177353812,51.6316001822,609.6 -2.2192554313,51.6287972192,609.6 -2.2202319857,51.625902032,609.6 -2.2206514358,51.6229552762,609.6 -2.2205080007,51.6199983237,609.6 -2.219803803,51.61707268150001,609.6 -2.2185488324,51.6142194095,609.6 -2.2167607997,51.6114785441,609.6 -2.2144648831,51.6088885376,609.6 -2.2116933704,51.6064857195,609.6 -2.2084852023,51.60430378819999,609.6 -2.204885424,51.6023733396,609.6 -2.2009445523,51.60072143979999,609.6 -2.1967178674,51.5993712465,609.6 -2.1922646389,51.5983416863,609.6 -2.1876472979,51.59764718980001,609.6 -2.1829305648,51.59729749109999,609.6 -2.1781805463,51.59729749109999,609.6 -2.1734638132,51.59764718980001,609.6 -2.1688464722,51.5983416863,609.6 -2.1643932438,51.5993712465,609.6 -2.1601665588,51.60072143979999,609.6 -2.1562256871,51.6023733396,609.6 -2.1526259088,51.60430378819999,609.6 -2.1494177407,51.6064857195,609.6 -2.146646228,51.6088885376,609.6 -2.1443503114,51.6114785441,609.6 -2.1425622788,51.6142194095,609.6 -2.1413073081,51.61707268150001,609.6 -2.1406031104,51.6199983237,609.6 -2.1404596754,51.6229552762,609.6 -2.1408791254,51.625902032,609.6 -2.1418556798,51.6287972192,609.6 -2.1433757299,51.6316001822,609.6 -2.1454180245,51.6342715531,609.6 -2.147953963,51.63677380549999,609.6 -2.1509479938,51.6390717828,609.6 -2.1543581097,51.6411331935,609.6 -2.1581364371,51.6429290662,609.6 -2.1622299078,51.6444341583,609.6 -2.1665810059,51.64562731180001,609.6 -2.1711285777,51.6464917528,609.6 -2.1758086946,51.6470153274,609.6 -2.1805555556,51.6471906741,609.6 + + + + +
+ + EGR106 RAYMILL HOUSE, LACOCK + A circle, 1 NM radius, centred at 512523N 0020646W
Upper limit: 1600 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Services;
any aircraft flying in the service of Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight.

Flying in accordance with an agreed exemption issued by, or with the permission of, the Wiltshire Police Constabulary Royalty Protection Department.

SI 703/2021.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1127777778,51.4397017704,487.68 -2.1166558753,51.4395243139,487.68 -2.1204512294,51.4389957307,487.68 -2.1240828677,51.4381272985,487.68 -2.1274733213,51.4369375448,487.68 -2.1305502821,51.43545185089999,487.68 -2.1332481474,51.4337019086,487.68 -2.1355094204,51.4317250426,487.68 -2.1372859347,51.42956341279999,487.68 -2.1385398793,51.42726311289999,487.68 -2.1392445993,51.42487318680001,487.68 -2.1393851584,51.4224445816,487.68 -2.13895865,51.4200290607,487.68 -2.1379742516,51.4176781007,487.68 -2.136453022,51.4154417947,487.68 -2.1344274453,51.4133677857,487.68 -2.1319407342,51.4115002529,487.68 -2.1290459045,51.4098789722,487.68 -2.1258046448,51.408538471,487.68 -2.122286002,51.40750729410001,487.68 -2.1185649125,51.4068073981,487.68 -2.1147206105,51.4064536847,487.68 -2.110834945,51.4064536847,487.68 -2.106990643,51.4068073981,487.68 -2.1032695536,51.40750729410001,487.68 -2.0997509107,51.408538471,487.68 -2.096509651,51.4098789722,487.68 -2.0936148214,51.4115002529,487.68 -2.0911281102,51.4133677857,487.68 -2.0891025336,51.4154417947,487.68 -2.0875813039,51.4176781007,487.68 -2.0865969056,51.4200290607,487.68 -2.0861703972,51.4224445816,487.68 -2.0863109563,51.42487318680001,487.68 -2.0870156763,51.42726311289999,487.68 -2.0882696209,51.42956341279999,487.68 -2.0900461352,51.4317250426,487.68 -2.0923074081,51.4337019086,487.68 -2.0950052735,51.43545185089999,487.68 -2.0980822343,51.4369375448,487.68 -2.1014726879,51.4381272985,487.68 -2.1051043261,51.4389957307,487.68 -2.1088996802,51.4395243139,487.68 -2.1127777778,51.4397017704,487.68 + + + + +
+ + EGR153 HINKLEY POINT + A circle, 2 NM radius, centred at 511233N 0030749W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hinkley Point, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight permitted by a helicopter flying within the Bridgewater Bay Danger Area with the permission of the person in charge of that Area and in accordance with any conditions to which that permission is subject which remains at least 1 NM from the position given at column 1 for Hinkley Point.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1301805556,51.2423352721,609.6 -3.1356343719,51.2421586853,609.6 -3.141030252399999,51.24163080089999,609.6 -3.1463108803,51.24075722639999,609.6 -3.1514201712,51.239547241,609.6 -3.1563038717,51.23801369660001,609.6 -3.1609101384,51.2361728802,609.6 -3.1651900912,51.23404434020001,609.6 -3.1690983329,51.2316506773,609.6 -3.1725934322,51.229017304,609.6 -3.1756383627,51.2261721727,609.6 -3.178200894600001,51.22314547860001,609.6 -3.1802539342,51.21996933749999,609.6 -3.1817758082,51.21667744429999,609.6 -3.1827504897,51.2133047149,609.6 -3.183167763400001,51.2098869144,609.6 -3.183023329200001,51.2064602785,609.6 -3.1823188426,51.2030611281,609.6 -3.181061891500001,51.1997254852,609.6 -3.179265911199999,51.1964886911,609.6 -3.1769500369,51.1933850325,609.6 -3.174138896900001,51.190447379,609.6 -3.1708623484,51.1877068364,609.6 -3.167155158,51.1851924178,609.6 -3.1630566323,51.182930738,609.6 -3.1586102005,51.180945733,609.6 -3.153862955,51.1792584078,609.6 -3.1488651536,51.17788661520001,609.6 -3.1436696898,51.17684486809999,609.6 -3.1383315354,51.17614418700001,609.6 -3.1329071624,51.17579198369999,609.6 -3.1274539487,51.17579198369999,609.6 -3.1220295757,51.17614418700001,609.6 -3.116691421300001,51.17684486809999,609.6 -3.1114959575,51.17788661520001,609.6 -3.1064981561,51.1792584078,609.6 -3.1017509106,51.180945733,609.6 -3.0973044788,51.182930738,609.6 -3.0932059531,51.1851924178,609.6 -3.0894987627,51.1877068364,609.6 -3.0862222142,51.190447379,609.6 -3.0834110742,51.1933850325,609.6 -3.0810951999,51.1964886911,609.6 -3.0792992196,51.1997254852,609.6 -3.0780422685,51.2030611281,609.6 -3.0773377819,51.2064602785,609.6 -3.0771933477,51.2098869144,609.6 -3.0776106214,51.2133047149,609.6 -3.0785853029,51.21667744429999,609.6 -3.0801071769,51.21996933749999,609.6 -3.0821602165,51.22314547860001,609.6 -3.084722748399999,51.2261721727,609.6 -3.0877676789,51.229017304,609.6 -3.0912627782,51.2316506773,609.6 -3.0951710199,51.23404434020001,609.6 -3.0994509727,51.2361728802,609.6 -3.1040572394,51.23801369660001,609.6 -3.1089409399,51.239547241,609.6 -3.1140502308,51.24075722639999,609.6 -3.1193308587,51.24163080089999,609.6 -3.124726739200001,51.2421586853,609.6 -3.1301805556,51.2423352721,609.6 + + + + +
+ + EGR154 OLDBURY + A circle, 2 NM radius, centred at 513852N 0023415W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Oldbury, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5708638889,51.6811522104,609.6 -2.5763702602,51.68097563490001,609.6 -2.5818181352,51.6804477843,609.6 -2.5871496433,51.6795742659,609.6 -2.5923081578,51.67836435870001,609.6 -2.597238901,51.67683091410001,609.6 -2.6018895292,51.6749902186,609.6 -2.6062106904,51.6728618197,609.6 -2.6101565501,51.6704683175,609.6 -2.613685278,51.66783512319999,609.6 -2.6167594919,51.664990188,609.6 -2.6193466528,51.66196370550001,609.6 -2.6214194077,51.6587877899,609.6 -2.6229558766,51.6554961341,609.6 -2.6239398805,51.6521236517,609.6 -2.6243611085,51.6487061056,609.6 -2.6242152215,51.6452797286,609.6 -2.6235038936,51.6418808392,609.6 -2.6222347885,51.6385454562,609.6 -2.6204214729,51.63530891790001,609.6 -2.6180832685,51.6322055079,609.6 -2.6152450422,51.62926809290001,609.6 -2.6119369398,51.6265277754,609.6 -2.6081940633,51.6240135655,609.6 -2.6040560978,51.62175207540001,609.6 -2.5995668902,51.6197672383,609.6 -2.5947739853,51.6180800568,609.6 -2.5897281231,51.61670838180001,609.6 -2.5844827046,51.6156667245,609.6 -2.5790932284,51.6149661039,609.6 -2.5736167077,51.6146139311,609.6 -2.5681110701,51.6146139311,609.6 -2.5626345494,51.6149661039,609.6 -2.5572450732,51.6156667245,609.6 -2.5519996547,51.61670838180001,609.6 -2.5469537925,51.6180800568,609.6 -2.5421608876,51.6197672383,609.6 -2.53767168,51.62175207540001,609.6 -2.5335337145,51.6240135655,609.6 -2.529790838,51.6265277754,609.6 -2.5264827356,51.62926809290001,609.6 -2.5236445093,51.6322055079,609.6 -2.5213063049,51.63530891790001,609.6 -2.5194929893,51.6385454562,609.6 -2.5182238841,51.6418808392,609.6 -2.5175125563,51.6452797286,609.6 -2.5173666693,51.6487061056,609.6 -2.5177878972,51.6521236517,609.6 -2.5187719012,51.6554961341,609.6 -2.5203083701,51.6587877899,609.6 -2.522381125,51.66196370550001,609.6 -2.5249682859,51.664990188,609.6 -2.5280424998,51.66783512319999,609.6 -2.5315712277,51.6704683175,609.6 -2.5355170874,51.6728618197,609.6 -2.5398382486,51.6749902186,609.6 -2.5444888768,51.67683091410001,609.6 -2.54941962,51.67836435870001,609.6 -2.5545781345,51.6795742659,609.6 -2.5599096425,51.6804477843,609.6 -2.5653575176,51.68097563490001,609.6 -2.5708638889,51.6811522104,609.6 + + + + +
+ + EGR155 BERKELEY + A circle, 2 NM radius, centred at 514134N 0022936W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Berkeley, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4933,51.7260130658,609.6 -2.4988118196,51.7258364915,609.6 -2.504265085,51.7253086443,609.6 -2.5096018678,51.72443513160001,609.6 -2.5147654852,51.7232252324,609.6 -2.5197011053,51.7216917979,609.6 -2.5243563324,51.7198511147,609.6 -2.5286817657,51.7177227303,609.6 -2.5326315251,51.7153292444,609.6 -2.5361637393,51.7126960683,609.6 -2.539240989,51.7098511531,609.6 -2.5418307031,51.70682469219999,609.6 -2.5439055018,51.7036487996,609.6 -2.5454434837,51.700357168,609.6 -2.5464284541,51.6969847108,609.6 -2.5468500919,51.6935671906,609.6 -2.5467040542,51.69014084009999,609.6 -2.5459920171,51.68674197730001,609.6 -2.5447216519,51.6834066208,609.6 -2.5429065392,51.6801701086,609.6 -2.5405660198,51.6770667241,609.6 -2.5377249855,51.67412933340001,609.6 -2.5344136119,51.6713890388,609.6 -2.5306670359,51.6688748503,609.6 -2.5265249817,51.6666133795,609.6 -2.5220313396,51.6646285596,609.6 -2.5172337012,51.6629413928,609.6 -2.5121828567,51.6615697298,609.6 -2.5069322595,51.66052808170001,609.6 -2.5015374629,51.6598274673,609.6 -2.4960555361,51.6594752976,609.6 -2.4905444639,51.6594752976,609.6 -2.4850625371,51.6598274673,609.6 -2.4796677405,51.66052808170001,609.6 -2.4744171433,51.6615697298,609.6 -2.4693662988,51.6629413928,609.6 -2.4645686604,51.6646285596,609.6 -2.4600750183,51.6666133795,609.6 -2.4559329641,51.6688748503,609.6 -2.4521863881,51.6713890388,609.6 -2.4488750145,51.67412933340001,609.6 -2.4460339802,51.6770667241,609.6 -2.4436934608,51.6801701086,609.6 -2.4418783481,51.6834066208,609.6 -2.4406079829,51.68674197730001,609.6 -2.4398959458,51.69014084009999,609.6 -2.4397499081,51.6935671906,609.6 -2.4401715459,51.6969847108,609.6 -2.4411565163,51.700357168,609.6 -2.4426944982,51.7036487996,609.6 -2.4447692969,51.70682469219999,609.6 -2.447359011,51.7098511531,609.6 -2.4504362607,51.7126960683,609.6 -2.4539684749,51.7153292444,609.6 -2.4579182343,51.7177227303,609.6 -2.4622436676,51.7198511147,609.6 -2.4668988947,51.7216917979,609.6 -2.4718345148,51.7232252324,609.6 -2.4769981322,51.72443513160001,609.6 -2.482334915,51.7253086443,609.6 -2.4877881804,51.7258364915,609.6 -2.4933,51.7260130658,609.6 + + + + +
+ + EGR156 WINDSOR CASTLE + A circle, 1.25 NM radius, centred at 512902N 0003614W
Upper limit: 2500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft operating for or on behalf of National Police Air Service;
any aircraft operating for or on behalf of The Helicopter Emergency Medical Service;
any aircraft operating for or on behalf of The Maritime and Coastguard Agency for the purposes of search and rescue operations;
any aircraft operating for or on behalf of The King's Helicopter Flight;
any aircraft operated by a member of the Royal Family;
any aircraft flying in accordance with an agreed exemption issued by, or with the permission of, the Metropolitan Police (Royalty and Special Protection);
or landing in the grounds of Windsor Great Park at the invitation of the Director of Royal Travel provided that Protective Security Operations (PSO) has been informed in advance of such intended flight or landing;
any aircraft approaching to, or departing from, London Heathrow Airport.

SI 1137/2021.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6038888889,51.5046964329,762 -0.6082407864,51.50451834100001,762 -0.6125181213999999,51.5039871169,762 -0.6166476141,51.5031118618,762 -0.6205585275,51.5019075706,762 -0.6241838830999999,51.5003948741,762 -0.6274616116,51.4985996837,762 -0.630335617,51.4965527468,762 -0.6327567375000001,51.4942891181,762 -0.634683586,51.4918475578,762 -0.6360832551,51.4892698664,762 -0.6369318764,51.48660016809999,762 -0.6372150232,51.4838841541,762 -0.6369279509,51.4811683001,762 -0.6360756717,51.4784990711,762 -0.6346728614,51.4759221263,762 -0.6327436027,51.4734815389,762 -0.630320967,51.47121904320001,762 -0.6274464448,51.46917332219999,762 -0.6241692331000001,51.4673793477,762 -0.6205453926,51.4658677841,762 -0.6166368896,51.4646644659,762 -0.612510538,51.4637899573,762 -0.6082368609,51.46325920240001,762 -0.6038888889,51.4630812707,762 -0.5995409168,51.46325920240001,762 -0.5952672398,51.4637899573,762 -0.5911408882,51.4646644659,762 -0.5872323852,51.4658677841,762 -0.5836085447,51.4673793477,762 -0.5803313329999999,51.46917332219999,762 -0.5774568108,51.47121904320001,762 -0.5750341751,51.4734815389,762 -0.5731049163,51.4759221263,762 -0.5717021061000001,51.4784990711,762 -0.5708498268,51.4811683001,762 -0.5705627546000001,51.4838841541,762 -0.5708459014,51.48660016809999,762 -0.5716945227,51.4892698664,762 -0.5730941918,51.4918475578,762 -0.5750210402,51.4942891181,762 -0.5774421608,51.4965527468,762 -0.5803161661,51.4985996837,762 -0.5835938946,51.5003948741,762 -0.5872192503,51.5019075706,762 -0.5911301637,51.5031118618,762 -0.5952596563,51.5039871169,762 -0.5995369914000001,51.50451834100001,762 -0.6038888889,51.5046964329,762 + + + + +
+ + EGR157 HYDE PARK + 513212N 0000911W -
513020N 0000648W thence clockwise by the arc of a circle radius 0.55 NM centred on 513000N 0000730W to
513001N 0000637W -
512917N 0000634W thence clockwise by the arc of a circle radius 0.55 NM centred on 512915N 0000726W to
512852N 0000649W -
512834N 0000719W thence clockwise by the arc of a circle radius 0.55 NM centred on 512857N 0000756W to
512858N 0000849W -
512921N 0000847W -
512939N 0001132W thence clockwise by the arc of a circle radius 0.55 NM centred on 513011N 0001123W to
513028N 0001209W -
513208N 0001038W thence clockwise by the arc of a circle radius 0.55 NM centred on 513151N 0000952W to -
513212N 0000911W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 1300/2017

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1529333333,51.53661111109999,426.7200000000001 -0.1549267573,51.53789408709999,426.7200000000001 -0.1572818369,51.5389111961,426.7200000000001 -0.1599088899,51.5396236997,426.7200000000001 -0.1627078613,51.5400044583,426.7200000000001 -0.1655721364,51.5400389683,426.7200000000001 -0.1683926087,51.5397259152,426.7200000000001 -0.1710618431,51.5390772237,426.7200000000001 -0.1734781752,51.53811760280001,426.7200000000001 -0.1755495885,51.5368836029,426.7200000000001 -0.1771972222,51.5354222222,426.7200000000001 -0.2023722222,51.5076638889,426.7200000000001 -0.2035115549,51.5060699613,426.7200000000001 -0.2041447262,51.5043699176,426.7200000000001 -0.2042494731,51.5026257804,426.7200000000001 -0.2038220493,51.5009009245,426.7200000000001 -0.2028780428,51.4992580171,426.7200000000001 -0.2014518003,51.4977567415,426.7200000000001 -0.1995951734,51.4964516304,426.7200000000001 -0.1973756297,51.4953900866,426.7200000000001 -0.1948738011,51.4946106635,426.7200000000001 -0.1921805556,51.4941416667,426.7200000000001 -0.1464694444,51.4890388889,426.7200000000001 -0.1468722222,51.48287500000001,426.7200000000001 -0.1467340709,51.4811955082,426.7200000000001 -0.1461068208,51.4795600798,426.7200000000001 -0.1450111174,51.4780238809,426.7200000000001 -0.1434839716,51.4766387391,426.7200000000001 -0.141576937,51.4754513811,426.7200000000001 -0.1393543671,51.47450185809999,426.7200000000001 -0.1368912443,51.47382219699999,426.7200000000001 -0.1342706517,51.4734353207,426.7200000000001 -0.1315809745,51.4733542773,426.7200000000001 -0.1289129236,51.4735818,426.7200000000001 -0.1263564821,51.4741102153,426.7200000000001 -0.1239978753,51.4749217016,426.7200000000001 -0.1219166667,51.4759888889,426.7200000000001 -0.1136111111,51.48111111110001,426.7200000000001 -0.1120090522,51.482252708,426.7200000000001 -0.1107683543,51.483560414,426.7200000000001 -0.109891236,51.4849782611,426.7200000000001 -0.1094019057,51.4864671731,426.7200000000001 -0.1093138889,51.4879861111,426.7200000000001 -0.1102416667,51.5003194444,426.7200000000001 -0.1105268172,51.5017362939,426.7200000000001 -0.1111609871,51.50310830229999,426.7200000000001 -0.1121293381,51.50440206899999,426.7200000000001 -0.1134083333,51.5055861111,426.7200000000001 -0.1529333333,51.53661111109999,426.7200000000001 + + + + +
+ + EGR158 CITY OF LONDON + 513125N 0000547W -
513118N 0000439W -
513043N 0000418W -
513016N 0000433W -
513037N 0000704W -
513108N 0000653W -
513125N 0000547W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 2092/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.09652500000000001,51.52371388890001,426.7200000000001 -0.1147444444,51.5188833333,426.7200000000001 -0.1176944444,51.5102972222,426.7200000000001 -0.0757138889,51.5044888889,426.7200000000001 -0.0716472222,51.51206666669999,426.7200000000001 -0.07758611109999999,51.5216055556,426.7200000000001 -0.09652500000000001,51.52371388890001,426.7200000000001 + + + + +
+ + EGR159 ISLE OF DOGS + 513035N 0000025W -
512954N 0000033W -
512938N 0000022W thence clockwise by the arc of a circle radius 0.3 NM centred on 512931N 0000049W to
512921N 0000113W -
513000N 0000154W thence clockwise by the arc of a circle radius 0.55 NM centred on 513018N 0000110W to -
513035N 0000025W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit;
any aircraft approaching to, or departing from, London/City Airport.

See also ENR 1.1, paragraph 4.1.6.

SI 2091/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0068583333,51.5097055556,426.7200000000001 -0.0082867913,51.5111814939,426.7200000000001 -0.0103077723,51.5123684169,426.7200000000001 -0.0126486151,51.51329883229999,426.7200000000001 -0.0152268831,51.5139399674,426.7200000000001 -0.0179517632,51.51426923799999,426.7200000000001 -0.020727269,51.51427504499999,426.7200000000001 -0.0234556276,51.5139571838,426.7200000000001 -0.0260407298,51.5133268516,426.7200000000001 -0.0283915214,51.51240625220001,426.7200000000001 -0.030425215,51.5112278124,426.7200000000001 -0.0320702078,51.5098330386,426.7200000000001 -0.0332686036,51.50827105250001,426.7200000000001 -0.0339782479,51.5065968595,426.7200000000001 -0.0341742076,51.5048694103,426.7200000000001 -0.0338496416,51.5031495242,426.7200000000001 -0.033016033,51.5014977474,426.7200000000001 -0.0317027778,51.4999722222,426.7200000000001 -0.0202666667,51.48911111110001,426.7200000000001 -0.0187899397,51.4881604117,426.7200000000001 -0.0170196811,51.4874451822,426.7200000000001 -0.0150110296,51.4870446916,426.7200000000001 -0.0129044713,51.4869869497,426.7200000000001 -0.0108473335,51.4872759947,426.7200000000001 -0.008983490199999999,51.4878916114,426.7200000000001 -0.0074433086,51.4887907435,426.7200000000001 -0.0063345359,51.4899105027,426.7200000000001 -0.005734762,51.4911725642,426.7200000000001 -0.005685986,51.49248864270001,426.7200000000001 -0.0061916667,51.4937666667,426.7200000000001 -0.009272222199999999,51.49840277780001,426.7200000000001 -0.0068583333,51.5097055556,426.7200000000001 + + + + +
+ + EGR217 SIZEWELL + A circle, 2 NM radius, centred at 521250N 0013707E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sizewell, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.6186111111,52.2471767692,609.6 1.6130349418,52.2470002081,609.6 1.6075180128,52.24647240069999,609.6 1.602118931,52.2455989541,609.6 1.596895043,52.2443891468,609.6 1.5919018227,52.2428558299,609.6 1.5871922788,52.241015289,609.6 1.5828163894,52.2388870708,609.6 1.5788205702,52.2364937743,609.6 1.5752471812,52.23386080929999,609.6 1.5721340772,52.2310161253,609.6 1.5695142078,52.2279899142,609.6 1.5674152705,52.2248142877,609.6 1.5658594196,52.22152293649999,609.6 1.5648630359,52.2181507711,609.6 1.5644365577,52.2147335516,609.6 1.5645843754,52.2113075073,609.6 1.5653047901,52.2079089532,609.6 1.5665900379,52.2045739043,609.6 1.5684263769,52.201337695,609.6 1.5707942383,52.198234605,609.6 1.5736684378,52.19529749679999,609.6 1.5770184465,52.19255746899999,609.6 1.5808087168,52.190043528,609.6 1.5849990611,52.1877822821,609.6 1.5895450777,52.1857976613,609.6 1.5943986212,52.184110665,609.6 1.5995083107,52.1827391416,609.6 1.6048200718,52.1816975999,609.6 1.6102777059,52.1809970574,609.6 1.6158234815,52.1806449239,609.6 1.6213987407,52.1806449239,609.6 1.6269445163,52.1809970574,609.6 1.6324021504,52.1816975999,609.6 1.6377139115,52.1827391416,609.6 1.642823601,52.184110665,609.6 1.6476771445,52.1857976613,609.6 1.6522231611,52.1877822821,609.6 1.6564135054,52.190043528,609.6 1.6602037757,52.19255746899999,609.6 1.6635537844,52.19529749679999,609.6 1.6664279839,52.198234605,609.6 1.6687958453,52.201337695,609.6 1.6706321843,52.2045739043,609.6 1.6719174321,52.2079089532,609.6 1.6726378469,52.2113075073,609.6 1.6727856645,52.2147335516,609.6 1.6723591863,52.2181507711,609.6 1.6713628027,52.22152293649999,609.6 1.6698069517,52.2248142877,609.6 1.6677080144,52.2279899142,609.6 1.6650881451,52.2310161253,609.6 1.661975041,52.23386080929999,609.6 1.658401652,52.2364937743,609.6 1.6544058329,52.2388870708,609.6 1.6500299435,52.241015289,609.6 1.6453203995,52.2428558299,609.6 1.6403271792,52.2443891468,609.6 1.6351032913,52.2455989541,609.6 1.6297042095,52.24647240069999,609.6 1.6241872805,52.2470002081,609.6 1.6186111111,52.2471767692,609.6 + + + + +
+ + EGR219 SANDRINGHAM HOUSE + 524819N 0003104E thence clockwise by the arc of a circle radius 1.5 NM centred on 524948N 0003049E to
525117N 0003033E -
525132N 0003424E thence anti-clockwise by the arc of a circle radius 1.5 NM centred on 525003N 0003447E to
524834N 0003510E -
524819N 0003104E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;
any aircraft landing in the grounds of Sandringham House at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended landing.

SI 1734/2015.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5177777778,52.80527777780001,609.6 0.5861111111,52.8094444444,609.6 0.5813312013,52.8091625577,609.6 0.5765296282,52.8092184194,609.6 0.5717711605,52.80961150990001,609.6 0.5671200484,52.8103365217,609.6 0.5626390999000001,52.8113836653,609.6 0.5583888366,52.81273880060001,609.6 0.5544266794,52.8143836274,609.6 0.5508061755,52.8162959307,609.6 0.5475762763000001,52.8184498803,609.6 0.5447806761,52.82081637770001,609.6 0.5424572208,52.8233634481,609.6 0.5406373936,52.82605667120001,609.6 0.5393458868,52.8288596452,609.6 0.5386002629,52.8317344777,609.6 0.5384107123,52.8346422975,609.6 0.5387799094,52.8375437796,609.6 0.5397029712,52.8403996768,609.6 0.5411675166,52.8431713511,609.6 0.5431538286000001,52.8458212968,609.6 0.5456351161,52.8483136486,609.6 0.5485778725,52.8506146684,609.6 0.5519423253,52.8526932029,609.6 0.5556829735,52.85452110690001,609.6 0.559749202,52.8560736255,609.6 0.5640859678,52.85732973109999,609.6 0.5686345472,52.8582724089,609.6 0.5733333333,52.8588888889,609.6 0.5091666667,52.8547222222,609.6 0.5044716918,52.8542266656,609.6 0.4998968511,52.85342217749999,609.6 0.4955069903,52.8523021167,609.6 0.4913613018999999,52.8508815899,609.6 0.4875156698,52.8491797549,609.6 0.4840219144,52.8472195607,609.6 0.4809270925,52.8450274369,609.6 0.4782728636,52.8426329362,609.6 0.4760949294,52.8400683345,609.6 0.4744225554,52.8373681946,609.6 0.4732781803,52.8345688996,609.6 0.4726771183999999,52.8317081614,609.6 0.4726273583,52.8288245125,609.6 0.4731294608,52.825956786,609.6 0.4741765578,52.8231435933,609.6 0.4757544502,52.8204228042,609.6 0.4778418043000001,52.81783103770001,609.6 0.4804104435,52.81540317,609.6 0.483425732,52.8131718661,609.6 0.4868470429,52.81116714169999,609.6 0.4906283068,52.80941596089999,609.6 0.4947186319,52.8079418741,609.6 0.4990629881,52.8067647034,609.6 0.5036029447,52.8059002767,609.6 0.5082774536,52.8053602162,609.6 0.513023667,52.8051517825,609.6 0.5177777778,52.80527777780001,609.6 + + + + +
+ + EGR220 ANMER HALL + A circle, 1.5 NM radius, centred at 525003N 0003447E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of National Police Air Service;
any aircraft flying in the service of the Helicopter Emergency Medical Service;
any aircraft flying in the service of the Maritime and Coastguard Agency;
any aircraft flying in the service of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit;
any aircraft either operated by a member of the Royal Family, or landing in the grounds of Anmer Hall at the invitation of the person in charge of the household there, provided that the Norfolk and Suffolk Constabulary Royalty and VIP Protection Unit has been informed in advance of such intended flight or landing.

SI 1735/2015.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5797222222,52.859129963,609.6 0.5748442042,52.8589546483,609.6 0.5700347793,52.8584311691,609.6 0.5653615715,52.85756688639999,609.6 0.5608902795,52.8563739525,609.6 0.5566837497,52.8548691396,609.6 0.5528010891,52.8530736028,609.6 0.5492968325000001,52.85101258160001,609.6 0.5462201754,52.8487150433,609.6 0.5436142829,52.84621327499999,609.6 0.5415156856,52.8435424277,609.6 0.539953769,52.8407400216,609.6 0.5389503657,52.8378454177,609.6 0.5385194541,52.8348992641,609.6 0.5386669678,52.8319429244,609.6 0.5393907192,52.829017897,609.6 0.5406804363,52.82616523259999,609.6 0.5425179136,52.8234249585,609.6 0.5448772732,52.8208355175,609.6 0.5477253323,52.8184332298,609.6 0.5510220733,52.81625178510001,609.6 0.5547212068,52.81432177100001,609.6 0.5587708226,52.8126702457,609.6 0.5631141169,52.8113203607,609.6 0.5676901877,52.81029103670001,609.6 0.5724348857,52.8095967002,609.6 0.5772817097,52.8092470821,609.6 0.5821627347,52.8092470821,609.6 0.5870095588000001,52.8095967002,609.6 0.5917542567,52.81029103670001,609.6 0.5963303275,52.8113203607,609.6 0.6006736219,52.8126702457,609.6 0.6047232376,52.81432177100001,609.6 0.6084223711,52.81625178510001,609.6 0.6117191121,52.8184332298,609.6 0.6145671713,52.8208355175,609.6 0.6169265308,52.8234249585,609.6 0.6187640082,52.82616523259999,609.6 0.6200537253,52.829017897,609.6 0.6207774766,52.8319429244,609.6 0.6209249903,52.8348992641,609.6 0.6204940787,52.8378454177,609.6 0.6194906755,52.8407400216,609.6 0.6179287589,52.8435424277,609.6 0.6158301615,52.84621327499999,609.6 0.613224269,52.8487150433,609.6 0.6101476119,52.85101258160001,609.6 0.6066433553,52.8530736028,609.6 0.6027606947,52.8548691396,609.6 0.5985541649,52.8563739525,609.6 0.594082873,52.85756688639999,609.6 0.5894096651,52.8584311691,609.6 0.5846002403,52.8589546483,609.6 0.5797222222,52.859129963,609.6 + + + + +
+ + EGR311 CAPENHURST + A circle, 2 NM radius, centred at 531550N 0025708W
Upper limit: 2200 FT MSL
Lower limit: SFC
Class: SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9522222222,53.2971708423,670.5600000000001 -2.9579341894,53.2969943076,670.5600000000001 -2.9635854683,53.2964665791,670.5600000000001 -2.9691160199,53.2955932635,670.5600000000001 -2.9744670965,53.29438363889999,670.5600000000001 -2.9795818698,53.2928505553,670.5600000000001 -2.9844060374,53.2910102972,670.5600000000001 -2.9888884027,53.2888824097,670.5600000000001 -2.9929814192,53.2864894898,670.5600000000001 -2.9966416966,53.2838569448,670.5600000000001 -2.9998304605,53.2810127215,670.5600000000001 -3.0025139625,53.2779870081,670.5600000000001 -3.0046638354,53.2748119126,670.5600000000001 -3.0062573909,53.2715211209,670.5600000000001 -3.0072778557,53.2681495386,670.5600000000001 -3.007714544200001,53.26473292,670.5600000000001 -3.0075629662,53.2613074885,670.5600000000001 -3.0068248687,53.25790955219999,670.5600000000001 -3.0055082113,53.2545751195,670.5600000000001 -3.0036270764,53.2513395174,670.5600000000001 -3.0012015142,53.248237018,670.5600000000001 -2.9982573261,53.2453004767,670.5600000000001 -2.9948257867,53.2425609844,670.5600000000001 -2.9909433102,53.2400475405,670.5600000000001 -2.9866510624,53.23778674650001,670.5600000000001 -2.981994524000001,53.2358025259,670.5600000000001 -2.9770230091,53.2341158725,670.5600000000001 -2.9717891449,53.2327446297,670.5600000000001 -2.9663483163,53.2317033022,670.5600000000001 -2.9607580832,53.2310029042,670.5600000000001 -2.955077575,53.2306508436,670.5600000000001 -2.9493668694,53.2306508436,670.5600000000001 -2.9436863612,53.2310029042,670.5600000000001 -2.9380961281,53.2317033022,670.5600000000001 -2.9326552995,53.2327446297,670.5600000000001 -2.927421435299999,53.2341158725,670.5600000000001 -2.9224499205,53.2358025259,670.5600000000001 -2.917793382,53.23778674650001,670.5600000000001 -2.9135011342,53.2400475405,670.5600000000001 -2.9096186577,53.2425609844,670.5600000000001 -2.9061871184,53.2453004767,670.5600000000001 -2.903242930199999,53.248237018,670.5600000000001 -2.9008173681,53.2513395174,670.5600000000001 -2.8989362332,53.2545751195,670.5600000000001 -2.897619575799999,53.25790955219999,670.5600000000001 -2.8968814782,53.2613074885,670.5600000000001 -2.8967299002,53.26473292,670.5600000000001 -2.8971665887,53.2681495386,670.5600000000001 -2.8981870536,53.2715211209,670.5600000000001 -2.8997806091,53.2748119126,670.5600000000001 -2.901930482,53.2779870081,670.5600000000001 -2.9046139839,53.2810127215,670.5600000000001 -2.9078027478,53.2838569448,670.5600000000001 -2.911463025200001,53.2864894898,670.5600000000001 -2.915556041699999,53.2888824097,670.5600000000001 -2.920038406999999,53.2910102972,670.5600000000001 -2.924862574700001,53.2928505553,670.5600000000001 -2.9299773479,53.29438363889999,670.5600000000001 -2.9353284246,53.2955932635,670.5600000000001 -2.9408589761,53.2964665791,670.5600000000001 -2.946510255,53.2969943076,670.5600000000001 -2.9522222222,53.2971708423,670.5600000000001 + + + + +
+ + EGR312 SPRINGFIELDS + A circle, 2 NM radius, centred at 534634N 0024815W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted at not less than 1670 FT above mean sea level for the purpose of landing at Blackpool Airport.

Flight permitted in airspace lying south of a straight line drawn from 534644N 0024454W to 534513N 0025044W for the purpose of landing at or taking off from Warton Aerodrome.

Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Springfields, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8041666667,53.8093901962,640.08 -2.8099480329,53.8092136741,640.08 -2.8156679709,53.8086859834,640.08 -2.8212657095,53.8078127308,640.08 -2.8266817852,53.8066031939,640.08 -2.8318586771,53.8050702223,640.08 -2.836741422,53.8032301001,640.08 -2.8412782002,53.8011023716,640.08 -2.8454208877,53.7987096328,640.08 -2.8491255674,53.7960772901,640.08 -2.852352995,53.7932332887,640.08 -2.855069014,53.7902078153,640.08 -2.857244915,53.787032976,640.08 -2.8588577369,53.78374245450001,640.08 -2.859890506,53.780371154,640.08 -2.8603324101,53.7769548261,640.08 -2.8601789083,53.7735296912,640.08 -2.8594317722,53.77013205429999,640.08 -2.8580990616,53.7667979202,640.08 -2.8561950329,53.7635626126,640.08 -2.8537399825,53.7604604,640.08 -2.850760027000001,53.7575241339,640.08 -2.8472868223,53.7547849019,640.08 -2.8433572254,53.7522716996,640.08 -2.839012901999999,53.7500111253,640.08 -2.8342998842,53.7480270994,640.08 -2.829268083400001,53.7463406129,640.08 -2.8239707635,53.7449695067,640.08 -2.8184639791,53.7439282835,640.08 -2.8128059857,53.7432279559,640.08 -2.807056627,53.7428759307,640.08 -2.8012767063,53.7428759307,640.08 -2.7955273476,53.7432279559,640.08 -2.7898693542,53.7439282835,640.08 -2.7843625699,53.7449695067,640.08 -2.7790652499,53.7463406129,640.08 -2.7740334492,53.7480270994,640.08 -2.7693204313,53.7500111253,640.08 -2.7649761079,53.7522716996,640.08 -2.7610465111,53.7547849019,640.08 -2.7575733064,53.7575241339,640.08 -2.7545933508,53.7604604,640.08 -2.7521383004,53.7635626126,640.08 -2.7502342717,53.7667979202,640.08 -2.7489015611,53.77013205429999,640.08 -2.748154425,53.7735296912,640.08 -2.7480009232,53.7769548261,640.08 -2.7484428274,53.780371154,640.08 -2.7494755964,53.78374245450001,640.08 -2.7510884183,53.787032976,640.08 -2.7532643193,53.7902078153,640.08 -2.7559803383,53.7932332887,640.08 -2.759207766,53.7960772901,640.08 -2.7629124456,53.7987096328,640.08 -2.7670551331,53.8011023716,640.08 -2.7715919114,53.8032301001,640.08 -2.7764746563,53.8050702223,640.08 -2.7816515482,53.8066031939,640.08 -2.7870676238,53.8078127308,640.08 -2.7926653624,53.8086859834,640.08 -2.7983853004,53.8092136741,640.08 -2.8041666667,53.8093901962,640.08 + + + + +
+ + EGR313 SCAMPTON + A circle, 5 NM radius, centred at 531828N 0003303W
Upper limit: 9500 FT MSL
Lower limit: SFC
Class: Contact: Information on activation status may be obtained from Waddington ATC, Tel: 01522-727451/727452, or by radio to Waddington Zone on 119.500 MHz/232.700 MHz.

Non-radio aircraft may be able to obtain a pre-flight clearance by telephone. Radio equipped aircraft may request an in-flight clearance to enter EGR313 from Waddington Zone on 119.500/232.700 MHz.

SI 2023/879.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5508333332999999,53.3909816953,2895.6 -0.5599365630000001,53.3908032038,2895.6 -0.5690005838,53.3902684981,2895.6 -0.5779863586,53.389379881,2895.6 -0.5868551933,53.38814117969999,2895.6 -0.595568906,53.38655772839999,2895.6 -0.6040899937999999,53.38463634539999,2895.6 -0.6123817972,53.382385303,2895.6 -0.6204086597,53.3798142914,2895.6 -0.6281360829,53.3769343765,2895.6 -0.6355308768,53.3737579512,2895.6 -0.6425613032,53.3702986815,2895.6 -0.6491972133,53.366571447,2895.6 -0.6554101771,53.3625922757,2895.6 -0.6611736056,53.3583782744,2895.6 -0.6664628642,53.3539475544,2895.6 -0.6712553778,53.34931915249999,2895.6 -0.6755307254,53.3445129487,2895.6 -0.6792707268,53.33954958,2895.6 -0.6824595172,53.3344503507,2895.6 -0.6850836134,53.3292371409,2895.6 -0.687131968,53.3239323115,2895.6 -0.6885960136,53.3185586082,2895.6 -0.6894696963,53.3131390634,2895.6 -0.6897494974,53.3076968973,2895.6 -0.6894344449000001,53.3022554181,2895.6 -0.688526114,53.29683792239999,2895.6 -0.687028616,53.2914675952,2895.6 -0.6849485775,53.2861674113,2895.6 -0.6822951079,53.2809600368,2895.6 -0.6790797571,53.2758677328,2895.6 -0.6753164628,53.2709122608,2895.6 -0.6710214883,53.2661147902,2895.6 -0.6662133499,53.2614958084,2895.6 -0.6609127355,53.2570750343,2895.6 -0.6551424149,53.25287133449999,2895.6 -0.6489271405,53.2489026439,2895.6 -0.6422935407,53.2451858903,2895.6 -0.6352700061,53.2417369221,2895.6 -0.6278865675999999,53.2385704427,2895.6 -0.6201747691,53.23569994799999,2895.6 -0.6121675334,53.2331376696,2895.6 -0.6038990228,53.230894524,2895.6 -0.5954044954,53.22898006629999,2895.6 -0.5867201563,53.22740245039999,2895.6 -0.5778830057,53.22616839459999,2895.6 -0.5689306834,53.22528315380001,2895.6 -0.5599013112,53.2247504972,2895.6 -0.5508333332999999,53.22457269260001,2895.6 -0.5417653554,53.2247504972,2895.6 -0.5327359832,53.22528315380001,2895.6 -0.5237836608999999,53.22616839459999,2895.6 -0.5149465103,53.22740245039999,2895.6 -0.5062621713,53.22898006629999,2895.6 -0.4977676438999999,53.230894524,2895.6 -0.4894991333000001,53.2331376696,2895.6 -0.4814918975,53.23569994799999,2895.6 -0.473780099,53.2385704427,2895.6 -0.4663966606,53.2417369221,2895.6 -0.459373126,53.2451858903,2895.6 -0.4527395262,53.2489026439,2895.6 -0.4465242516999999,53.25287133449999,2895.6 -0.4407539310999999,53.2570750343,2895.6 -0.4354533168,53.2614958084,2895.6 -0.4306451783,53.2661147902,2895.6 -0.4263502038,53.2709122608,2895.6 -0.4225869096,53.2758677328,2895.6 -0.4193715588,53.2809600368,2895.6 -0.4167180891,53.2861674113,2895.6 -0.4146380506,53.2914675952,2895.6 -0.4131405527,53.29683792239999,2895.6 -0.4122322218,53.3022554181,2895.6 -0.4119171693,53.3076968973,2895.6 -0.4121969703,53.3131390634,2895.6 -0.413070653,53.3185586082,2895.6 -0.4145346987,53.3239323115,2895.6 -0.4165830533,53.3292371409,2895.6 -0.4192071494,53.3344503507,2895.6 -0.4223959399,53.33954958,2895.6 -0.4261359411999999,53.3445129487,2895.6 -0.4304112889,53.34931915249999,2895.6 -0.4352038024,53.3539475544,2895.6 -0.4404930611,53.3583782744,2895.6 -0.4462564895,53.3625922757,2895.6 -0.4524694533,53.366571447,2895.6 -0.4591053634,53.3702986815,2895.6 -0.4661357899,53.3737579512,2895.6 -0.4735305838,53.3769343765,2895.6 -0.481258007,53.3798142914,2895.6 -0.4892848694,53.382385303,2895.6 -0.4975766729,53.38463634539999,2895.6 -0.5060977607,53.38655772839999,2895.6 -0.5148114733,53.38814117969999,2895.6 -0.5236803081,53.389379881,2895.6 -0.5326660828999999,53.3902684981,2895.6 -0.5417301037,53.3908032038,2895.6 -0.5508333332999999,53.3909816953,2895.6 + + + + +
+ + EGR322 WYLFA + A circle, 2 NM radius, centred at 532458N 0042852W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted at a height of not less than 2000 FT above ground level whilst operating under and in accordance with a clearance from the air traffic control unit at RAF Valley.

Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Wylfa, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4812194444,53.4493672106,640.08 -4.4869518094,53.4491906797,640.08 -4.4926232685,53.44866296239999,640.08 -4.4981735678,53.4477896656,640.08 -4.5035437489,53.4465800672,640.08 -4.5086767801,53.445047017,640.08 -4.5135181648,53.4432067994,640.08 -4.5180165232,53.4410789594,640.08 -4.5221241391,53.4386860935,640.08 -4.5257974674,53.4360536087,640.08 -4.5289975955,53.43320945160001,640.08 -4.531690655,53.4301838097,640.08 -4.5338481782,53.4270087905,640.08 -4.5354473967,53.42371807930001,640.08 -4.5364714781,53.4203465809,640.08 -4.5369096997,53.41693004890001,640.08 -4.5367575564,53.4135047057,640.08 -4.5360168024,53.4101068585,640.08 -4.5346954268,53.4067725146,640.08 -4.532807563,53.4035370001,640.08 -4.5303733337,53.4004345861,640.08 -4.5274186328,53.39749812660001,640.08 -4.5239748471,53.3947587118,640.08 -4.5200785209,53.3922453397,640.08 -4.5157709669,53.389984611,640.08 -4.5110978279,53.38800044830001,640.08 -4.5061085937,53.3863138446,640.08 -4.5008560783,53.3849426423,640.08 -4.4953958637,53.3839013458,640.08 -4.4897857142,53.3832009688,640.08 -4.4840849692,53.3828489187,640.08 -4.4783539196,53.3828489187,640.08 -4.4726531746,53.3832009688,640.08 -4.4670430252,53.3839013458,640.08 -4.4615828106,53.3849426423,640.08 -4.4563302952,53.3863138446,640.08 -4.451341061,53.38800044830001,640.08 -4.4466679219,53.389984611,640.08 -4.442360368,53.3922453397,640.08 -4.4384640418,53.3947587118,640.08 -4.4350202561,53.39749812660001,640.08 -4.4320655552,53.4004345861,640.08 -4.4296313259,53.4035370001,640.08 -4.4277434621,53.4067725146,640.08 -4.4264220865,53.4101068585,640.08 -4.4256813325,53.4135047057,640.08 -4.4255291891,53.41693004890001,640.08 -4.4259674108,53.4203465809,640.08 -4.4269914922,53.42371807930001,640.08 -4.4285907107,53.4270087905,640.08 -4.4307482339,53.4301838097,640.08 -4.4334412934,53.43320945160001,640.08 -4.4366414215,53.4360536087,640.08 -4.4403147498,53.4386860935,640.08 -4.4444223657,53.4410789594,640.08 -4.4489207241,53.4432067994,640.08 -4.4537621088,53.445047017,640.08 -4.45889514,53.4465800672,640.08 -4.4642653211,53.4477896656,640.08 -4.4698156203,53.44866296239999,640.08 -4.4754870795,53.4491906797,640.08 -4.4812194444,53.4493672106,640.08 + + + + +
+ + EGR413 SELLAFIELD + A circle, 2 NM radius, centred at 542505N 0032944W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Sellafield, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4955555556,54.451331069,609.6 -3.5014269937,54.4511545625,609.6 -3.5072360431,54.4506269186,609.6 -3.5129209825,54.44975374380001,609.6 -3.5184214188,54.4485443153,609.6 -3.5236789329,54.4470114824,609.6 -3.5286377032,54.4451715284,609.6 -3.5332451019,54.44304399690001,609.6 -3.537452255,54.4406514827,609.6 -3.5412145619,54.4380193906,609.6 -3.5444921685,54.43517566460001,609.6 -3.5472503885,54.4321504892,609.6 -3.5494600685,54.4289759681,609.6 -3.5510978936,54.4256857826,609.6 -3.5521466295,54.42231483260001,609.6 -3.5525953007,54.4188988665,609.6 -3.5524392998,54.415474101,609.6 -3.551680431,54.4120768371,609.6 -3.5503268838,54.4087430754,609.6 -3.5483931406,54.4055081352,609.6 -3.5458998173,54.40240628039999,609.6 -3.54287344,54.399470358,609.6 -3.5393461593,54.3967314511,609.6 -3.535355407,54.3942185508,609.6 -3.5309434975,54.3919582512,609.6 -3.5261571785,54.3899744688,609.6 -3.5210471366,54.38828819099999,609.6 -3.5156674621,54.3869172556,609.6 -3.5100750787,54.3858761629,609.6 -3.5043291446,54.3851759235,609.6 -3.4984904303,54.3848239427,609.6 -3.4926206808,54.3848239427,609.6 -3.4867819665,54.3851759235,609.6 -3.4810360324,54.3858761629,609.6 -3.475443649,54.3869172556,609.6 -3.470063974499999,54.38828819099999,609.6 -3.4649539326,54.3899744688,609.6 -3.4601676136,54.3919582512,609.6 -3.4557557041,54.3942185508,609.6 -3.4517649518,54.3967314511,609.6 -3.4482376711,54.399470358,609.6 -3.4452112938,54.40240628039999,609.6 -3.4427179705,54.4055081352,609.6 -3.4407842274,54.4087430754,609.6 -3.4394306801,54.4120768371,609.6 -3.4386718113,54.415474101,609.6 -3.4385158104,54.4188988665,609.6 -3.4389644816,54.42231483260001,609.6 -3.4400132175,54.4256857826,609.6 -3.4416510426,54.4289759681,609.6 -3.443860722600001,54.4321504892,609.6 -3.4466189426,54.43517566460001,609.6 -3.4498965493,54.4380193906,609.6 -3.4536588561,54.4406514827,609.6 -3.4578660092,54.44304399690001,609.6 -3.4624734079,54.4451715284,609.6 -3.4674321783,54.4470114824,609.6 -3.4726896923,54.4485443153,609.6 -3.478190128700001,54.44975374380001,609.6 -3.483875068,54.4506269186,609.6 -3.4896841174,54.4511545625,609.6 -3.4955555556,54.451331069,609.6 + + + + +
+ + EGR444 HEYSHAM + A circle, 2 NM radius, centred at 540147N 0025452W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Heysham, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Microlight access to Middleton Sands obtained from BMAA head office.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.914422222199999,54.06309155930001,609.6 -2.9202387654,54.0629150434,609.6 -2.9259935051,54.0623873713,609.6 -2.931625299399999,54.06151414950001,609.6 -2.9370743215,54.0603046557,609.6 -2.9422826999,54.0587717391,609.6 -2.9471951361,54.05693168370001,609.6 -2.9517594948,54.0548040333,609.6 -2.955927359,54.0524113837,609.6 -2.9596545448,54.0497791404,609.6 -2.9629015698,54.04693524820001,609.6 -2.9656340704,54.0439098929,609.6 -2.9678231638,54.0407351798,609.6 -2.9694457509,54.03744479140001,609.6 -2.970484756,54.0340736299,609.6 -2.9709293033,54.03065744530001,609.6 -2.9707748258,54.02723245669999,609.6 -2.9700231078,54.0238349675,609.6 -2.9686822598,54.0205009808,609.6 -2.9667666265,54.0172658186,609.6 -2.9642966289,54.0141637476,609.6 -2.9612985437,54.0112276176,609.6 -2.957804219899999,54.0084885142,609.6 -2.9538507391,54.0059754314,609.6 -2.9494800202,54.0037149657,609.6 -2.9447383748,54.0017310361,609.6 -2.9396760171,54.0000446322,609.6 -2.9343465338,53.9986735935,609.6 -2.9288063188,53.99763242189999,609.6 -2.9231139803,53.9969321292,609.6 -2.9173297239,53.9965801216,609.6 -2.9115147206,53.9965801216,609.6 -2.9057304642,53.9969321292,609.6 -2.9000381256,53.99763242189999,609.6 -2.8944979107,53.9986735935,609.6 -2.8891684273,54.0000446322,609.6 -2.8841060697,54.0017310361,609.6 -2.879364424299999,54.0037149657,609.6 -2.8749937053,54.0059754314,609.6 -2.8710402245,54.0084885142,609.6 -2.8675459008,54.0112276176,609.6 -2.8645478155,54.0141637476,609.6 -2.862077817999999,54.0172658186,609.6 -2.8601621846,54.0205009808,609.6 -2.8588213367,54.0238349675,609.6 -2.8580696187,54.02723245669999,609.6 -2.8579151412,54.03065744530001,609.6 -2.8583596884,54.0340736299,609.6 -2.8593986936,54.03744479140001,609.6 -2.8610212806,54.0407351798,609.6 -2.8632103741,54.0439098929,609.6 -2.8659428747,54.04693524820001,609.6 -2.8691898996,54.0497791404,609.6 -2.8729170854,54.0524113837,609.6 -2.8770849496,54.0548040333,609.6 -2.8816493083,54.05693168370001,609.6 -2.8865617445,54.0587717391,609.6 -2.8917701229,54.0603046557,609.6 -2.897219145,54.06151414950001,609.6 -2.9028509393,54.0623873713,609.6 -2.908605679,54.0629150434,609.6 -2.914422222199999,54.06309155930001,609.6 + + + + +
+ + EGR445 BARROW IN FURNESS + A circle, 0.5 NM radius, centred at 540635N 0031410W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Barrow in Furness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2361111111,54.118041546,609.6 -3.2389617203,54.1178712153,609.6 -3.2416955575,54.1173672007,609.6 -3.2442006422,54.1165501481,609.6 -3.2463743796,54.11545352480001,609.6 -3.248127766,54.1141222467,609.6 -3.249389035,54.112610836,609.6 -3.2501065925,54.110981186,609.6 -3.250251122,54.10930002449999,609.6 -3.2498167752,54.1076361805,609.6 -3.2488214002,54.1060577659,609.6 -3.2473058003,54.104629388,609.6 -3.2453320547,54.10340950680001,609.6 -3.2429809723,54.1024480441,609.6 -3.2403487825,54.1017843434,609.6 -3.2375432,54.1014455622,609.6 -3.2346790222,54.1014455622,609.6 -3.2318734397,54.1017843434,609.6 -3.2292412499,54.1024480441,609.6 -3.2268901675,54.10340950680001,609.6 -3.2249164219,54.104629388,609.6 -3.223400821999999,54.1060577659,609.6 -3.2224054471,54.1076361805,609.6 -3.2219711003,54.10930002449999,609.6 -3.2221156297,54.110981186,609.6 -3.2228331872,54.112610836,609.6 -3.2240944562,54.1141222467,609.6 -3.2258478426,54.11545352480001,609.6 -3.22802158,54.1165501481,609.6 -3.2305266648,54.1173672007,609.6 -3.233260501899999,54.1178712153,609.6 -3.2361111111,54.118041546,609.6 + + + + +
+ + EGR446 HARTLEPOOL + A circle, 2 NM radius, centred at 543807N 0011049W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hartlepool, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

Flight at a height of not less than 1800 FT amsl whilst conducting an instrument approach procedure at Teesside International Airport.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1802777778,54.66855208879999,609.6 -1.1861805046,54.6683755875,609.6 -1.192020509,54.6678479593,609.6 -1.1977357397,54.66697481050001,609.6 -1.2032654807,54.6657654184,609.6 -1.2085510006,54.66423263189999,609.6 -1.2135361801,54.6623927343,609.6 -1.2181681102,54.6602652688,609.6 -1.2223976566,54.6578728299,609.6 -1.2261799812,54.655240822,609.6 -1.2294750182,54.6523971884,609.6 -1.2322478972,54.649372113,609.6 -1.2344693105,54.64619769899999,609.6 -1.2361158203,54.6429076263,609.6 -1.2371701022,54.6395367943,609.6 -1.2376211234,54.63612095000001,609.6 -1.2374642539,54.6326963088,609.6 -1.2367013088,54.62929917059999,609.6 -1.2353405231,54.6259655344,609.6 -1.2333964576,54.62273071800001,609.6 -1.2308898392,54.6196289839,609.6 -1.2278473362,54.6166931775,609.6 -1.224301271,54.61395438029999,609.6 -1.2202892752,54.611441582,609.6 -1.2158538885,54.6091813752,609.6 -1.2110421072,54.60719767500001,609.6 -1.2059048872,54.6055114677,609.6 -1.2004966058,54.6041405901,609.6 -1.1948744885,54.60309954139999,609.6 -1.189098007,54.6023993318,609.6 -1.1832282541,54.60204736599999,609.6 -1.1773273015,54.60204736599999,609.6 -1.1714575485,54.6023993318,609.6 -1.1656810671,54.60309954139999,609.6 -1.1600589498,54.6041405901,609.6 -1.1546506683,54.6055114677,609.6 -1.1495134483,54.60719767500001,609.6 -1.144701667,54.6091813752,609.6 -1.1402662803,54.611441582,609.6 -1.1362542845,54.61395438029999,609.6 -1.1327082194,54.6166931775,609.6 -1.1296657163,54.6196289839,609.6 -1.127159098,54.62273071800001,609.6 -1.1252150324,54.6259655344,609.6 -1.1238542467,54.62929917059999,609.6 -1.1230913017,54.6326963088,609.6 -1.1229344322,54.63612095000001,609.6 -1.1233854534,54.6395367943,609.6 -1.1244397352,54.6429076263,609.6 -1.126086245,54.64619769899999,609.6 -1.1283076584,54.649372113,609.6 -1.1310805374,54.6523971884,609.6 -1.1343755744,54.655240822,609.6 -1.138157899,54.6578728299,609.6 -1.1423874453,54.6602652688,609.6 -1.1470193755,54.6623927343,609.6 -1.1520045549,54.66423263189999,609.6 -1.1572900749,54.6657654184,609.6 -1.1628198159,54.66697481050001,609.6 -1.1685350466,54.6678479593,609.6 -1.1743750509,54.6683755875,609.6 -1.1802777778,54.66855208879999,609.6 + + + + +
+ + EGR515 HUNTERSTON + A circle, 2 NM radius, centred at 554317N 0045338W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Hunterston, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.8938888889,55.7546572369,609.6 -4.8999545473,55.75448076140001,609.6 -4.9059557454,55.7539532102,609.6 -4.9118287131,55.7530801894,609.6 -4.9175110532,55.751870976,609.6 -4.9229424086,55.75033841810001,609.6 -4.9280651075,55.748498798,609.6 -4.9328247789,55.7463716576,609.6 -4.9371709319,55.74397958980001,609.6 -4.941057492,55.7413479969,609.6 -4.9444432906,55.7385048196,609.6 -4.9472924991,55.7354802387,609.6 -4.9495750068,55.7323063534,609.6 -4.9512667358,55.7290168396,609.6 -4.9523498915,55.7256465915,609.6 -4.9528131451,55.72223135069999,609.6 -4.9526517473,55.71880732649999,609.6 -4.9518675721,55.7154108119,609.6 -4.9504690896,55.71207779910001,609.6 -4.9484712699,55.7088435984,609.6 -4.9458954179,55.7057424646,609.6 -4.9427689426,55.7028072354,609.6 -4.9391250617,55.7000689844,609.6 -4.9350024464,55.697556694,609.6 -4.9304448098,55.6952969494,609.6 -4.9255004428,55.6933136592,609.6 -4.9202217032,55.6916278036,609.6 -4.9146644628,55.6902572139,609.6 -4.908887519,55.6892163852,609.6 -4.9029519762,55.6885163242,609.6 -4.8969206031,55.6881644332,609.6 -4.8908571746,55.6881644332,609.6 -4.8848258016,55.6885163242,609.6 -4.8788902587,55.6892163852,609.6 -4.873113315,55.6902572139,609.6 -4.8675560746,55.6916278036,609.6 -4.862277335,55.6933136592,609.6 -4.8573329679,55.6952969494,609.6 -4.8527753314,55.697556694,609.6 -4.8486527161,55.7000689844,609.6 -4.8450088351,55.7028072354,609.6 -4.8418823598,55.7057424646,609.6 -4.8393065079,55.7088435984,609.6 -4.8373086881,55.71207779910001,609.6 -4.8359102057,55.7154108119,609.6 -4.8351260305,55.71880732649999,609.6 -4.8349646327,55.72223135069999,609.6 -4.8354278863,55.7256465915,609.6 -4.836511042,55.7290168396,609.6 -4.838202771,55.7323063534,609.6 -4.8404852787,55.7354802387,609.6 -4.8433344872,55.7385048196,609.6 -4.8467202857,55.7413479969,609.6 -4.8506068459,55.74397958980001,609.6 -4.8549529988,55.7463716576,609.6 -4.8597126703,55.748498798,609.6 -4.8648353692,55.75033841810001,609.6 -4.8702667246,55.751870976,609.6 -4.8759490647,55.7530801894,609.6 -4.8818220324,55.7539532102,609.6 -4.8878232305,55.75448076140001,609.6 -4.8938888889,55.7546572369,609.6 + + + + +
+ + EGR516 TORNESS + A circle, 2 NM radius, centred at 555806N 0022431W
Upper limit: 2100 FT MSL
Lower limit: SFC
Class: Flight permitted for the purpose of landing at or taking off from the helicopter landing area at Torness, with the permission of the person in charge of the installation and in accordance with any conditions to which that permission is subject.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4084777778,56.0015392269,640.08 -2.4145820483,56.0013627571,640.08 -2.4206214466,56.00083522309999,640.08 -2.4265317954,55.9999622309,640.08 -2.4322502988,55.99875305729999,640.08 -2.4377162144,55.9972205504,640.08 -2.4428715028,55.9953809923,640.08 -2.4476614461,55.9932539246,640.08 -2.4520352321,55.9908619399,640.08 -2.4559464934,55.98823044,640.08 -2.4593537998,55.985387365,640.08 -2.4622210959,55.982362895,640.08 -2.4645180807,55.9791891284,640.08 -2.4662205246,55.9758997402,640.08 -2.4673105215,55.9725296235,640.08 -2.4677766727,55.9691145185,640.08 -2.4676142006,55.9656906333,640.08 -2.4668249932,55.9622942594,640.08 -2.4654175764,55.95896138730001,640.08 -2.4634070172,55.9557273257,640.08 -2.4608147578,55.9526263276,640.08 -2.4576683825,55.94969122879999,640.08 -2.4540013212,55.9469531015,640.08 -2.4498524916,55.94444092610001,640.08 -2.4452658848,55.94218128619999,640.08 -2.4402900985,55.9401980889,640.08 -2.4349778227,55.938512313,640.08 -2.4293852834,55.9371417886,640.08 -2.4235716504,55.9361010098,640.08 -2.4175984149,55.9354009824,640.08 -2.4115287429,55.9350491084,640.08 -2.4054268127,55.9350491084,640.08 -2.3993571407,55.9354009824,640.08 -2.3933839051,55.9361010098,640.08 -2.3875702722,55.9371417886,640.08 -2.3819777329,55.938512313,640.08 -2.376665457,55.9401980889,640.08 -2.3716896707,55.94218128619999,640.08 -2.367103064,55.94444092610001,640.08 -2.3629542344,55.9469531015,640.08 -2.3592871731,55.94969122879999,640.08 -2.3561407978,55.9526263276,640.08 -2.3535485383,55.9557273257,640.08 -2.3515379792,55.95896138730001,640.08 -2.3501305624,55.9622942594,640.08 -2.3493413549,55.9656906333,640.08 -2.3491788829,55.9691145185,640.08 -2.3496450341,55.9725296235,640.08 -2.350735031,55.9758997402,640.08 -2.3524374749,55.9791891284,640.08 -2.3547344596,55.982362895,640.08 -2.3576017558,55.985387365,640.08 -2.3610090622,55.98823044,640.08 -2.3649203235,55.9908619399,640.08 -2.3692941094,55.9932539246,640.08 -2.3740840528,55.9953809923,640.08 -2.3792393411,55.9972205504,640.08 -2.3847052568,55.99875305729999,640.08 -2.3904237602,55.9999622309,640.08 -2.3963341089,56.00083522309999,640.08 -2.4023735073,56.0013627571,640.08 -2.4084777778,56.0015392269,640.08 + + + + +
+ + EGR603 ROSYTH + A circle, 0.5 NM radius, centred at 560147N 0032703W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Flight permitted within the route notified as the Kelty Lane for the purpose of making an approach to land at, or a departure from, Edinburgh Airport.

SI 1003/2016.

Contact: CAA Airspace Regulation Operations, Tel: 01293-983880.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.450833333299999,56.0380389069,609.6 -3.4538238226,56.0378686278,609.6 -3.4566918046,56.0373647659,609.6 -3.4593197998,56.036547962,609.6 -3.4616001767,56.0354516743,609.6 -3.4634395644,56.0341208066,609.6 -3.464762678,56.0326098656,609.6 -3.4655153966,56.0309807265,609.6 -3.4656669719,56.0293000971,609.6 -3.465211276,56.0276367846,609.6 -3.4641670394,56.02605887879999,609.6 -3.4625770722,56.0246309652,609.6 -3.4605065022,56.0234114834,609.6 -3.4580401027,56.02245033740001,609.6 -3.4552788212,56.0217868563,609.6 -3.4523356513,56.0214481874,609.6 -3.4493310153,56.0214481874,609.6 -3.446387845499999,56.0217868563,609.6 -3.443626564,56.02245033740001,609.6 -3.4411601645,56.0234114834,609.6 -3.4390895945,56.0246309652,609.6 -3.4374996273,56.02605887879999,609.6 -3.4364553907,56.0276367846,609.6 -3.4359996948,56.0293000971,609.6 -3.4361512701,56.0309807265,609.6 -3.436903988700001,56.0326098656,609.6 -3.4382271022,56.0341208066,609.6 -3.44006649,56.0354516743,609.6 -3.4423468668,56.036547962,609.6 -3.4449748621,56.0373647659,609.6 -3.447842844,56.0378686278,609.6 -3.450833333299999,56.0380389069,609.6 + + + + +
+ + EGR610A THE HIGHLANDS + 583000N 0033902W -
582828N 0033815W -
582356N 0032847W -
580345N 0041248W -
580300N 0043000W -
580000N 0043700W -
574700N 0042500W -
573900N 0043000W -
573800N 0044500W -
573000N 0043800W -
571800N 0045200W -
571100N 0045300W -
570900N 0050000W -
570000N 0050200W -
565400N 0050500W -
565600N 0054700W -
571300N 0053500W -
575000N 0054300W -
580000N 0051500W -
583000N 0044900W -
583000N 0043000W -
582500N 0043000W -
583000N 0042000W -
583000N 0033902W
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Military Airspace Management Cell - Low Flying (MAMC LF) at RAF (U) Swanwick, Tel: 01489-443100.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.6505555556,58.5,1524 -4.3333333333,58.5,1524 -4.5,58.4166666667,1524 -4.5,58.5,1524 -4.8166666667,58.5,1524 -5.25,58.00000000000001,1524 -5.7166666667,57.8333333333,1524 -5.5833333333,57.2166666667,1524 -5.783333333299999,56.9333333333,1524 -5.0833333333,56.9,1524 -5.0333333333,57,1524 -5,57.15,1524 -4.8833333333,57.1833333333,1524 -4.8666666667,57.3,1524 -4.6333333333,57.49999999999999,1524 -4.75,57.6333333333,1524 -4.5,57.65,1524 -4.4166666667,57.7833333333,1524 -4.6166666667,58.00000000000001,1524 -4.5,58.05,1524 -4.2133333333,58.0625,1524 -3.4798583333,58.39885,1524 -3.6375,58.47444444440001,1524 -3.6505555556,58.5,1524 + + + + +
+ + EGR610B THE HIGHLANDS + 575000N 0054300W -
574004N 0054050W -
573840N 0055739W -
570000N 0055644W -
570000N 0061504W -
574715N 0061637W -
575000N 0054300W
Upper limit: 5000 FT MSL
Lower limit: 750 FT MSL
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,1524 -6.2769444444,57.7875,1524 -6.2511111111,57,1524 -5.9455555556,57,1524 -5.960833333300001,57.6444444444,1524 -5.680555555599999,57.6677777778,1524 -5.7166666667,57.8333333333,1524 + + + + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,228.6 -6.2769444444,57.7875,228.6 -6.2511111111,57,228.6 -5.9455555556,57,228.6 -5.960833333300001,57.6444444444,228.6 -5.680555555599999,57.6677777778,228.6 -5.7166666667,57.8333333333,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.7166666667,57.8333333333,228.6 -6.2769444444,57.7875,228.6 -6.2769444444,57.7875,1524 -5.7166666667,57.8333333333,1524 -5.7166666667,57.8333333333,228.6 + + + + + + relativeToGround + + + relativeToGround + + -6.2769444444,57.7875,228.6 -6.2511111111,57,228.6 -6.2511111111,57,1524 -6.2769444444,57.7875,1524 -6.2769444444,57.7875,228.6 + + + + + + relativeToGround + + + relativeToGround + + -6.2511111111,57,228.6 -5.9455555556,57,228.6 -5.9455555556,57,1524 -6.2511111111,57,1524 -6.2511111111,57,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.9455555556,57,228.6 -5.960833333300001,57.6444444444,228.6 -5.960833333300001,57.6444444444,1524 -5.9455555556,57,1524 -5.9455555556,57,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.960833333300001,57.6444444444,228.6 -5.680555555599999,57.6677777778,228.6 -5.680555555599999,57.6677777778,1524 -5.960833333300001,57.6444444444,1524 -5.960833333300001,57.6444444444,228.6 + + + + + + relativeToGround + + + relativeToGround + + -5.680555555599999,57.6677777778,228.6 -5.7166666667,57.8333333333,228.6 -5.7166666667,57.8333333333,1524 -5.680555555599999,57.6677777778,1524 -5.680555555599999,57.6677777778,228.6 + + + + + +
+ + EGR610C THE HIGHLANDS + 582218N 0033224W -
581434N 0031929W -
581121N 0032654W -
581900N 0033940W -
582218N 0033224W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.54,58.3716666667,609.6 -3.6611111111,58.3166666667,609.6 -3.4483333333,58.1891666667,609.6 -3.3247222222,58.24277777780001,609.6 -3.54,58.3716666667,609.6 + + + + +
+ + EGR610D THE HIGHLANDS + 574900N 0040606W -
574500N 0040254W -
574234N 0041056W -
573900N 0043000W -
574700N 0042500W -
574900N 0040606W
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: When active, entry of non-participating aircraft is prohibited unless flying in accordance with an authorisation given by the Low Flying Co-ord (LFC) at RAF (U) Swanwick, Tel: 01489-443100. Additionally a tactical clearance may be provided by the Range Control Officer for Tain Range during their hours of operation on 122.750 MHz.

In the event of an emergency which requires airborne assistance the HRA will be cleared of military low flying aircraft.

Clearance for emergency service aircraft will be given by Scottish Area Control Centre in conjunction with the LFC and the Aeronautical Rescue Co-ordination Centre.

New SI issued on activation.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1016666667,57.8166666667,609.6 -4.4166666667,57.7833333333,609.6 -4.5,57.65,609.6 -4.1822222222,57.7094444444,609.6 -4.0483333333,57.75000000000001,609.6 -4.1016666667,57.8166666667,609.6 + + + + +
+ + EGR704 BALMORAL + A circle, 1 NM radius, centred at 570227N 0031349W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
Any aircraft operated by or on behalf of Police Scotland;
any aircraft operated by or on behalf of the Scottish Air Ambulance Service;
any aircraft operated by or on behalf of the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;
any aircraft operated by or on behalf of The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —

Operated by a member of the Royal Family, or landing in the grounds of Balmoral at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.

SI 2019/1321.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2302777778,57.0574639676,1066.8 -3.234721726400001,57.0572866625,1066.8 -3.2390708352,57.05675853110001,1066.8 -3.2432322962,57.0558908441,1066.8 -3.2471173212,57.0547021176,1066.8 -3.250643042,57.05321771640001,1066.8 -3.2537342822,57.0514693109,1066.8 -3.2563251621,57.04949419960001,1066.8 -3.2583605024,57.04733451079999,1066.8 -3.2597969969,57.0450363023,1066.8 -3.260604129,57.0426485773,1066.8 -3.2607648138,57.0402222381,1066.8 -3.2602757524,57.0378090004,1066.8 -3.2591474911,57.0354602907,1066.8 -3.2574041866,57.033226151,1066.8 -3.2550830817,57.0311541735,1066.8 -3.2522337042,57.0292884884,1066.8 -3.2489168064,57.02766882600001,1066.8 -3.2452030682,57.02632967280001,1066.8 -3.2411715924,57.025299539,1066.8 -3.2369082222,57.0246003539,1066.8 -3.232503719,57.0242470008,1066.8 -3.2280518366,57.0242470008,1066.8 -3.223647333400001,57.0246003539,1066.8 -3.2193839632,57.025299539,1066.8 -3.215352487300001,57.02632967280001,1066.8 -3.2116387492,57.02766882600001,1066.8 -3.2083218513,57.0292884884,1066.8 -3.2054724739,57.0311541735,1066.8 -3.203151369,57.033226151,1066.8 -3.2014080645,57.0354602907,1066.8 -3.2002798032,57.0378090004,1066.8 -3.1997907417,57.0402222381,1066.8 -3.1999514266,57.0426485773,1066.8 -3.2007585587,57.0450363023,1066.8 -3.2021950531,57.04733451079999,1066.8 -3.2042303935,57.04949419960001,1066.8 -3.2068212734,57.0514693109,1066.8 -3.2099125136,57.05321771640001,1066.8 -3.2134382344,57.0547021176,1066.8 -3.2173232594,57.0558908441,1066.8 -3.2214847204,57.05675853110001,1066.8 -3.2258338292,57.0572866625,1066.8 -3.2302777778,57.0574639676,1066.8 + + + + +
+ + EGR705 BIRKHALL + A circle, 1 NM radius, centred at 570144N 0030427W
Upper limit: 3500 FT MSL
Lower limit: SFC
Class: Flight permitted by:
Any aircraft operated by, or on behalf of, Police Scotland;
any aircraft operated by, or on behalf of, the Scottish Air Ambulance Service;
any aircraft operated by, or on behalf of, the Maritime and Coastguard Agency for the purposes of a Search and Rescue operation;
any aircraft operated by, or on behalf of, The King's Helicopter Flight;
any aircraft flying in accordance with a permission issued by the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection, or either —

Operated by a member of the Royal Family,
or landing in the grounds of Birkhall at the invitation of the person in charge of the household there, provided that the Police Scotland Royalty and VIP Planning North Unit or the Metropolitan Police, Royalty and Specialist Protection has been informed in advance of such intended flight or landing.

SI 2019/1320.

Contact: Refer to Statutory Instrument.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0741666667,57.04551955510001,1066.8 -3.078609189,57.04534224970001,1066.8 -3.0829569019,57.0448141174,1066.8 -3.087117027500001,57.0439464289,1066.8 -3.091000805899999,57.04275770030001,1066.8 -3.0945253956,57.04127329649999,1066.8 -3.0976156443,57.0395248879,1066.8 -3.1002056935,57.037549773,1066.8 -3.1022403815,57.0353900803,1066.8 -3.1036764159,57.0330918675,1066.8 -3.10448329,57.030704138,1066.8 -3.1046439242,57.0282777942,1066.8 -3.1041550205,57.02586455180001,1066.8 -3.1030271218,57.0235158375,1066.8 -3.1012843771,57.0212816933,1066.8 -3.0989640172,57.0192097116,1066.8 -3.0961155538,57.01734402270001,1066.8 -3.0927997198,57.01572435689999,1066.8 -3.0890871725,57.01438520090001,1066.8 -3.0850569891,57.0133550649,1066.8 -3.0807949857,57.0126558784,1066.8 -3.076391894299999,57.01230252449999,1066.8 -3.071941439,57.01230252449999,1066.8 -3.0675383477,57.0126558784,1066.8 -3.0632763442,57.0133550649,1066.8 -3.0592461609,57.01438520090001,1066.8 -3.0555336136,57.01572435689999,1066.8 -3.0522177795,57.01734402270001,1066.8 -3.0493693162,57.0192097116,1066.8 -3.0470489562,57.0212816933,1066.8 -3.0453062115,57.0235158375,1066.8 -3.0441783129,57.02586455180001,1066.8 -3.0436894092,57.0282777942,1066.8 -3.0438500434,57.030704138,1066.8 -3.044656917400001,57.0330918675,1066.8 -3.0460929518,57.0353900803,1066.8 -3.0481276399,57.037549773,1066.8 -3.050717689,57.0395248879,1066.8 -3.0538079377,57.04127329649999,1066.8 -3.0573325274,57.04275770030001,1066.8 -3.0612163059,57.0439464289,1066.8 -3.0653764314,57.0448141174,1066.8 -3.0697241443,57.04534224970001,1066.8 -3.0741666667,57.04551955510001,1066.8 + + + + +
+ + EGRU001A LAND'S END + A circle, 2 NM radius, centred at 500610N 0054014W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6705805556,50.1360027382,609.6 -5.6759075942,50.13582612260001,609.6 -5.6811780483,50.135298152,609.6 -5.6863359382,50.1344244342,609.6 -5.691326487,50.1332142493,609.6 -5.6960967056,50.13168045030001,609.6 -5.7005959583,50.1298393258,609.6 -5.7047765024,50.12771042579999,609.6 -5.708593996199999,50.1253163537,609.6 -5.7120079707,50.1226825245,609.6 -5.714982258,50.1198368943,609.6 -5.717485374200001,50.1168096619,609.6 -5.7194908511,50.1136329477,609.6 -5.7209775143,50.1103404517,609.6 -5.7219297036,50.1069670951,609.6 -5.7223374351,50.1035486495,609.6 -5.7221965023,50.1001213569,609.6 -5.7215085159,50.0967215454,609.6 -5.720280881800001,50.09338524439999,609.6 -5.718526717599999,50.0901478028,609.6 -5.7162647094,50.087043515,609.6 -5.713518909699999,50.0841052587,609.6 -5.7103184794,50.0813641471,609.6 -5.706697376199999,50.07884920099999,609.6 -5.7026939937,50.0765870422,609.6 -5.6983507534,50.0746016133,609.6 -5.6937136564,50.0729139251,609.6 -5.6888317968,50.0715418357,609.6 -5.6837568442,50.0704998622,609.6 -5.6785424991,50.0697990282,609.6 -5.6732439281,50.0694467479,609.6 -5.667917183,50.0694467479,609.6 -5.662618612,50.0697990282,609.6 -5.6574042669,50.0704998622,609.6 -5.6523293143,50.0715418357,609.6 -5.6474474547,50.0729139251,609.6 -5.642810357700001,50.0746016133,609.6 -5.6384671174,50.0765870422,609.6 -5.634463734899999,50.07884920099999,609.6 -5.630842631700001,50.0813641471,609.6 -5.627642201399999,50.0841052587,609.6 -5.6248964017,50.087043515,609.6 -5.6226343935,50.0901478028,609.6 -5.6208802293,50.09338524439999,609.6 -5.6196525952,50.0967215454,609.6 -5.6189646089,50.1001213569,609.6 -5.6188236761,50.1035486495,609.6 -5.6192314075,50.1069670951,609.6 -5.6201835968,50.1103404517,609.6 -5.62167026,50.1136329477,609.6 -5.6236757369,50.1168096619,609.6 -5.626178853099999,50.1198368943,609.6 -5.6291531404,50.1226825245,609.6 -5.6325671149,50.1253163537,609.6 -5.6363846088,50.12771042579999,609.6 -5.640565152799999,50.1298393258,609.6 -5.6450644055,50.13168045030001,609.6 -5.649834624100001,50.1332142493,609.6 -5.6548251729,50.1344244342,609.6 -5.6599830628,50.135298152,609.6 -5.6652535169,50.13582612260001,609.6 -5.6705805556,50.1360027382,609.6 + + + + +
+ + EGRU001B LAND'S END RWY 02 + 500326N 0054128W -
500337N 0054215W -
500426N 0054148W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500414N 0054102W -
500326N 0054128W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6911472222,50.0572722222,609.6 -5.6838163611,50.0705099722,609.6 -5.688277730999999,50.0714098034,609.6 -5.6925948678,50.072565022,609.6 -5.696732583300001,50.0739661944,609.6 -5.7043,50.0602944444,609.6 -5.6911472222,50.0572722222,609.6 + + + + +
+ + EGRU001C LAND'S END RWY 20 + 500855N 0053919W -
500845N 0053832W -
500759N 0053857W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500808N 0053945W -
500855N 0053919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.655263888900001,50.1487388889,609.6 -5.662560111100001,50.135601,609.6 -5.6579724056,50.1350009132,609.6 -5.6534878727,50.13413688250001,609.6 -5.6491431944,50.133016,609.6 -5.642086111100001,50.1457166667,609.6 -5.655263888900001,50.1487388889,609.6 + + + + +
+ + EGRU001D LAND'S END RWY 07 + 500441N 0054420W -
500511N 0054441W -
500537N 0054314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500508N 0054254W -
500441N 0054420W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7388095556,50.0781908333,609.6 -5.7148789444,50.0854752222,609.6 -5.7171147379,50.0881153518,609.6 -5.7189715321,50.0908744357,609.6 -5.7204341389,50.09373,609.6 -5.744775305600001,50.0863204167,609.6 -5.7388095556,50.0781908333,609.6 + + + + +
+ + EGRU001E LAND'S END RWY 25 + 500738N 0053637W -
500708N 0053616W -
500650N 0053718W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500718N 0053741W -
500738N 0053637W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6103814444,50.1271384722,609.6 -5.6281196944,50.1217638889,609.6 -5.6256200098,50.1192229179,609.6 -5.6234872223,50.1165472972,609.6 -5.6217386667,50.1137588611,609.6 -5.6044106111,50.1190089444,609.6 -5.6103814444,50.1271384722,609.6 + + + + +
+ + EGRU001F LAND'S END RWY 11 + 500657N 0054430W -
500726N 0054411W -
500707N 0054258W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500637N 0054316W -
500657N 0054430W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7417068611,50.11570450000001,609.6 -5.7210458611,50.1101511389,609.6 -5.7197968384,50.11304867810001,609.6 -5.7181462876,50.1158619309,609.6 -5.7161076111,50.1185679444,609.6 -5.7363042222,50.1239965556,609.6 -5.7417068611,50.11570450000001,609.6 + + + + +
+ + EGRU001G LAND'S END RWY 29 + 500516N 0053607W -
500446N 0053627W -
500505N 0053737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500535N 0053716W -
500516N 0053607W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6019960278,50.08780683330001,609.6 -5.6210773611,50.0929611389,609.6 -5.6226464125,50.0901288342,609.6 -5.6246059681,50.087399098,609.6 -5.626939999999999,50.08479416669999,609.6 -5.6073946111,50.0795147222,609.6 -5.6019960278,50.08780683330001,609.6 + + + + +
+ + EGRU001H LAND'S END RWY 16 + 500843N 0054216W -
500855N 0054130W -
500806N 0054059W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500754N 0054146W -
500843N 0054216W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.704525,50.1452111111,609.6 -5.6961072222,50.1316766111,609.6 -5.691940084799999,50.1330387019,609.6 -5.6875986663,50.1341536005,609.6 -5.6831183889,50.1350122222,609.6 -5.6915305556,50.14854444440001,609.6 -5.704525,50.1452111111,609.6 + + + + +
+ + EGRU001I LAND'S END RWY 34 + 500334N 0053810W -
500322N 0053857W -
500413N 0053929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500610N 0054014W to
500425N 0053842W -
500334N 0053810W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.636175,50.0593444444,609.6 -5.6450833611,50.0737236667,609.6 -5.649245904,50.0723633887,609.6 -5.653581799,50.0712499565,609.6 -5.6580558056,50.0703924167,609.6 -5.649141666700001,50.0560111111,609.6 -5.636175,50.0593444444,609.6 + + + + +
+ + EGRU002A PENZANCE + A circle, 2 NM radius, centred at 500749N 0053050W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5139555556,50.1636886897,609.6 -5.5192856706,50.1635120748,609.6 -5.5245591683,50.1629841063,609.6 -5.5297200365,50.1621103922,609.6 -5.5347134667,50.1609002124,609.6 -5.539486439,50.15936641979999,609.6 -5.5439882886,50.157525303,609.6 -5.5481712449,50.1553964121,609.6 -5.5519909409,50.1530023503,609.6 -5.555406884,50.15036853260001,609.6 -5.5583828855,50.14752291489999,609.6 -5.5608874435,50.1444956961,609.6 -5.5628940747,50.1413189963,609.6 -5.5643815924,50.1380265155,609.6 -5.5653343275,50.1346531747,609.6 -5.5657422906,50.1312347453,609.6 -5.5656012729,50.1278074691,609.6 -5.5649128862,50.1244076743,609.6 -5.5636845407,50.12107138979999,609.6 -5.5619293619,50.1178339644,609.6 -5.5596660466,50.11472969239999,609.6 -5.5569186613,50.1117914512,609.6 -5.5537163839,50.10905035390001,609.6 -5.5500931917,50.106535421,609.6 -5.5460875004,50.10427327419999,609.6 -5.541741756,50.10228785589999,609.6 -5.5371019861,50.10060017679999,609.6 -5.532217313,50.0992280948,609.6 -5.5271394359,50.098186127,609.6 -5.5219220864,50.0974852968,609.6 -5.5166204626,50.0971330184,609.6 -5.5112906485,50.0971330184,609.6 -5.5059890247,50.0974852968,609.6 -5.5007716752,50.098186127,609.6 -5.4956937982,50.0992280948,609.6 -5.490809125,50.10060017679999,609.6 -5.4861693551,50.10228785589999,609.6 -5.4818236107,50.10427327419999,609.6 -5.4778179194,50.106535421,609.6 -5.4741947272,50.10905035390001,609.6 -5.4709924498,50.1117914512,609.6 -5.4682450646,50.11472969239999,609.6 -5.4659817493,50.1178339644,609.6 -5.4642265704,50.12107138979999,609.6 -5.4629982249,50.1244076743,609.6 -5.4623098382,50.1278074691,609.6 -5.4621688205,50.1312347453,609.6 -5.4625767836,50.1346531747,609.6 -5.4635295187,50.1380265155,609.6 -5.4650170364,50.1413189963,609.6 -5.4670236676,50.1444956961,609.6 -5.4695282256,50.14752291489999,609.6 -5.4725042271,50.15036853260001,609.6 -5.4759201702,50.1530023503,609.6 -5.4797398662,50.1553964121,609.6 -5.4839228226,50.157525303,609.6 -5.4884246721,50.15936641979999,609.6 -5.4931976444,50.1609002124,609.6 -5.4981910746,50.1621103922,609.6 -5.5033519428,50.1629841063,609.6 -5.5086254405,50.1635120748,609.6 -5.5139555556,50.1636886897,609.6 + + + + +
+ + EGRU002B PENZANCE RWY 08 + 500706N 0053454W -
500738N 0053503W -
500745N 0053357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to
500713N 0053348W -
500706N 0053454W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5817965278,50.11826600000001,609.6 -5.5633322778,50.1203276389,609.6 -5.5645434783,50.12322990009999,609.6 -5.5653429327,50.12619053510001,609.6 -5.5657240556,50.1291854444,609.6 -5.58417825,50.1271248889,609.6 -5.5817965278,50.11826600000001,609.6 + + + + +
+ + EGRU002C PENZANCE RWY 26 + 500833N 0052646W -
500801N 0052637W -
500754N 0052744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500749N 0053050W to
500826N 0052752W -
500833N 0052646W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.4460903889,50.1424680556,609.6 -5.46455675,50.1404263056,609.6 -5.4633515891,50.1375229498,609.6 -5.4625586488,50.13456158649999,609.6 -5.4621843333,50.1315663333,609.6 -5.4437078889,50.1336091944,609.6 -5.4460903889,50.1424680556,609.6 + + + + +
+ + EGRU003A CULDROSE + A circle, 2.5 NM radius, centred at 500507N 0051515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2540722222,50.1270222675,609.6 -5.2600465019,50.1268445494,609.6 -5.2659696794,50.1263129153,609.6 -5.271791093,50.1254319124,609.6 -5.2774609581,50.124209076,609.6 -5.282930796,50.1226548643,609.6 -5.2881538508,50.1207825685,609.6 -5.293085492,50.1186081982,609.6 -5.2976835968,50.1161503437,609.6 -5.3019089119,50.1134300161,609.6 -5.3057253884,50.1104704664,609.6 -5.3091004903,50.1072969857,609.6 -5.3120054703,50.1039366885,609.6 -5.3144156139,50.1004182793,609.6 -5.3163104478,50.0967718071,609.6 -5.3176739117,50.0930284076,609.6 -5.3184944912,50.08922003679999,609.6 -5.3187653125,50.0853791979,609.6 -5.3184841965,50.08153866340001,609.6 -5.3176536728,50.0777311953,609.6 -5.316280954,50.073989266,609.6 -5.3143778694,50.0703447816,609.6 -5.3119607606,50.06682881,609.6 -5.3090503379,50.06347131719999,609.6 -5.3056715012,50.06030091220001,609.6 -5.3018531249,50.0573446048,609.6 -5.2976278098,50.0546275756,609.6 -5.2930316047,50.0521729635,609.6 -5.2881036984,50.05000166889999,609.6 -5.2828860862,50.0481321775,609.6 -5.2774232136,50.04658040340001,609.6 -5.271761599,50.0453595547,609.6 -5.2659494404,50.0444800221,609.6 -5.2600362071,50.0439492907,609.6 -5.2540722222,50.0437718769,609.6 -5.2481082373,50.0439492907,609.6 -5.242195004,50.0444800221,609.6 -5.2363828454,50.0453595547,609.6 -5.2307212309,50.04658040340001,609.6 -5.2252583582,50.0481321775,609.6 -5.220040746,50.05000166889999,609.6 -5.2151128397,50.0521729635,609.6 -5.2105166346,50.0546275756,609.6 -5.2062913196,50.0573446048,609.6 -5.2024729432,50.06030091220001,609.6 -5.1990941066,50.06347131719999,609.6 -5.1961836839,50.06682881,609.6 -5.193766575,50.0703447816,609.6 -5.1918634905,50.073989266,609.6 -5.1904907716,50.0777311953,609.6 -5.1896602479,50.08153866340001,609.6 -5.1893791319,50.0853791979,609.6 -5.1896499532,50.08922003679999,609.6 -5.1904705327,50.0930284076,609.6 -5.1918339966,50.0967718071,609.6 -5.1937288306,50.1004182793,609.6 -5.1961389742,50.1039366885,609.6 -5.1990439541,50.1072969857,609.6 -5.202419056,50.1104704664,609.6 -5.2062355326,50.1134300161,609.6 -5.2104608476,50.1161503437,609.6 -5.2150589524,50.1186081982,609.6 -5.2199905936,50.1207825685,609.6 -5.2252136485,50.1226548643,609.6 -5.2306834863,50.124209076,609.6 -5.2363533515,50.1254319124,609.6 -5.2421747651,50.1263129153,609.6 -5.2480979426,50.1268445494,609.6 -5.2540722222,50.1270222675,609.6 + + + + +
+ + EGRU003B CULDROSE RWY 06 + 500339N 0051921W -
500408N 0051944W -
500423N 0051857W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500353N 0051837W -
500339N 0051921W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3224722222,50.0608,609.6 -5.3102815833,50.0648040278,609.6 -5.3124470945,50.067469965,609.6 -5.314308046,50.0702295787,609.6 -5.3158546667,50.0730684722,609.6 -5.3288083333,50.0688138889,609.6 -5.3224722222,50.0608,609.6 + + + + +
+ + EGRU003C CULDROSE RWY 24 + 500650N 0051129W -
500621N 0051106W -
500609N 0051142W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500637N 0051208W -
500650N 0051129W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1913138889,50.1138611111,609.6 -5.2022176389,50.11029775,609.6 -5.1995584017,50.10782339359999,609.6 -5.1971842309,50.10523193880001,609.6 -5.1951074722,50.1025369444,609.6 -5.1849694444,50.10585,609.6 -5.1913138889,50.1138611111,609.6 + + + + +
+ + EGRU003D CULDROSE RWY 11 + 500607N 0051959W -
500637N 0051939W -
500620N 0051838W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500550N 0051858W -
500607N 0051959W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3329861111,50.1018638889,609.6 -5.3160738056,50.0972953889,609.6 -5.3145814639,50.1001392694,609.6 -5.3127741935,50.1029065511,609.6 -5.3106613611,50.10558283329999,609.6 -5.3275583333,50.11014722219999,609.6 -5.3329861111,50.1018638889,609.6 + + + + +
+ + EGRU003E CULDROSE RWY 29 + 500408N 0051031W -
500338N 0051050W -
500355N 0051151W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500424N 0051132W -
500408N 0051031W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1752277778,50.0688777778,609.6 -5.19210275,50.0734629167,609.6 -5.1936019857,50.0706204565,609.6 -5.1954154024,50.06785489859999,609.6 -5.1975335278,50.0651806111,609.6 -5.1806444444,50.0605916667,609.6 -5.1752277778,50.0688777778,609.6 + + + + +
+ + EGRU003F CULDROSE RWY 18 + 500805N 0051538W -
500806N 0051448W -
500736N 0051447W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500737N 0051537W -
500805N 0051538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2606666667,50.1348166667,609.6 -5.26033425,50.1268269722,609.6 -5.2556702386,50.1270095639,609.6 -5.2509978848,50.1269752666,609.6 -5.2463415833,50.12672425,609.6 -5.2466861111,50.1350555556,609.6 -5.2606666667,50.1348166667,609.6 + + + + +
+ + EGRU003G CULDROSE RWY 36 + 500209N 0051433W -
500208N 0051524W -
500238N 0051525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 500507N 0051515W to
500240N 0051435W -
500209N 0051433W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2425861111,50.03572222219999,609.6 -5.2429433056,50.0443929444,609.6 -5.2475654006,50.04398315030001,609.6 -5.2522213076,50.0437889397,609.6 -5.2568868333,50.0438113333,609.6 -5.2565416667,50.03548333330001,609.6 -5.2425861111,50.03572222219999,609.6 + + + + +
+ + EGRU004A PREDANNACK + A circle, 2 NM radius, centred at 500007N 0051354W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2317694444,50.0353338744,609.6 -5.2370853375,50.0351572562,609.6 -5.2423447648,50.03462927759999,609.6 -5.2474918642,50.0337555467,609.6 -5.2524719738,50.0325453435,609.6 -5.2572322156,50.0310115211,609.6 -5.2617220602,50.0291703683,609.6 -5.2658938646,50.0270414353,609.6 -5.2697033803,50.0246473257,609.6 -5.2731102226,50.0220134548,609.6 -5.2760782991,50.0191677788,609.6 -5.2785761915,50.0161404971,609.6 -5.2805774868,50.0129637305,609.6 -5.2820610542,50.0096711794,609.6 -5.2830112659,50.0062977655,609.6 -5.2834181582,50.0028792609,609.6 -5.283277533,49.99945190819999,609.6 -5.2825909971,49.9960520364,609.6 -5.2813659402,49.9927156753,609.6 -5.2796154522,49.98947817460001,609.6 -5.2773581795,49.9863738295,609.6 -5.2746181242,49.9834355182,609.6 -5.2714243858,49.9806943547,609.6 -5.2678108511,49.9781793605,609.6 -5.2638158332,49.9759171581,609.6 -5.2594816653,49.9739316906,609.6 -5.2548542522,49.9722439694,609.6 -5.2499825859,49.9708718529,609.6 -5.2449182283,49.9698298588,609.6 -5.2397147684,49.96912901090001,609.6 -5.2344272576,49.9687767236,609.6 -5.2291116313,49.9687767236,609.6 -5.2238241205,49.96912901090001,609.6 -5.2186206606,49.9698298588,609.6 -5.213556303,49.9708718529,609.6 -5.2086846367,49.9722439694,609.6 -5.2040572236,49.9739316906,609.6 -5.1997230557,49.9759171581,609.6 -5.1957280378,49.9781793605,609.6 -5.1921145031,49.9806943547,609.6 -5.1889207647,49.9834355182,609.6 -5.1861807094,49.9863738295,609.6 -5.1839234367,49.98947817460001,609.6 -5.1821729487,49.9927156753,609.6 -5.1809478918,49.9960520364,609.6 -5.1802613559,49.99945190819999,609.6 -5.1801207307,50.0028792609,609.6 -5.180527623,50.0062977655,609.6 -5.1814778347,50.0096711794,609.6 -5.1829614021,50.0129637305,609.6 -5.1849626974,50.0161404971,609.6 -5.1874605898,50.0191677788,609.6 -5.1904286663,50.0220134548,609.6 -5.1938355086,50.0246473257,609.6 -5.1976450242,50.0270414353,609.6 -5.2018168287,50.0291703683,609.6 -5.2063066733,50.0310115211,609.6 -5.2110669151,50.0325453435,609.6 -5.2160470246,50.0337555467,609.6 -5.221194124,50.03462927759999,609.6 -5.2264535514,50.0351572562,609.6 -5.2317694444,50.0353338744,609.6 + + + + +
+ + EGRU004B PREDANNACK RWY 05 + 495742N 0051701W -
495805N 0051736W -
495854N 0051622W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495831N 0051546W -
495742N 0051701W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2835419444,49.9617730833,609.6 -5.2627449167,49.97538555559999,609.6 -5.2663444516,49.9772937977,609.6 -5.2696628728,49.979403434,609.6 -5.2726731667,49.9816973056,609.6 -5.2934640556,49.9680870278,609.6 -5.2835419444,49.9617730833,609.6 + + + + +
+ + EGRU004C PREDANNACK RWY 23 + 500232N 0051048W -
500209N 0051012W -
500121N 0051127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500143N 0051203W -
500232N 0051048W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1799270833,50.04227241670001,609.6 -5.2007712222,50.0286782778,609.6 -5.1971696359,50.0267686512,609.6 -5.1938502156,50.024657554,609.6 -5.19084,50.0223621944,609.6 -5.1699896944,50.03595852779999,609.6 -5.1799270833,50.04227241670001,609.6 + + + + +
+ + EGRU004D PREDANNACK RWY 09 + 495940N 0051842W -
500013N 0051843W -
500013N 0051700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495940N 0051656W -
495940N 0051842W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3117936944,49.9944973611,609.6 -5.2821116389,49.9945571944,609.6 -5.2829561989,49.9975243578,609.6 -5.2833808119,50.0005286115,609.6 -5.2833819167,50.0035453056,609.6 -5.3118256944,50.0034878056,609.6 -5.3117936944,49.9944973611,609.6 + + + + +
+ + EGRU004E PREDANNACK RWY 27 + 500013N 0050926W -
495941N 0050926W -
495941N 0051053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500013N 0051049W -
500013N 0050926W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1573170556,50.00371624999999,609.6 -5.180168,50.0036954167,609.6 -5.1801480057,50.00067875660001,609.6 -5.1805515819,49.9976733054,609.6 -5.1813753611,49.99470372219999,609.6 -5.1572850556,49.99472580559999,609.6 -5.1573170556,50.00371624999999,609.6 + + + + +
+ + EGRU004F PREDANNACK RWY 13 + 500131N 0051744W -
500157N 0051713W -
500127N 0051613W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500100N 0051641W -
500131N 0051744W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2954350278,50.0253619444,609.6 -5.2780854722,50.0167982778,609.6 -5.2758280709,50.0194338016,609.6 -5.2732102702,50.02192715809999,609.6 -5.2702534167,50.0242579444,609.6 -5.2869394444,50.0324947222,609.6 -5.2954350278,50.0253619444,609.6 + + + + +
+ + EGRU004G PREDANNACK RWY 31 + 495826N 0051006W -
495800N 0051037W -
495837N 0051152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495902N 0051119W -
495826N 0051006W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.1683617778,49.97384749999999,609.6 -5.1885124444,49.9838324444,609.6 -5.1912391424,49.9813889971,609.6 -5.1942966282,49.9791142377,609.6 -5.1976598889,49.9770267222,609.6 -5.1768470278,49.9667146667,609.6 -5.1683617778,49.97384749999999,609.6 + + + + +
+ + EGRU004H PREDANNACK RWY 18 + 500307N 0051420W -
500308N 0051330W -
500206N 0051328W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
500206N 0051419W -
500307N 0051420W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2389025278,50.05208019439999,609.6 -5.2384789167,50.0350520833,609.6 -5.2338293861,50.035307421,609.6 -5.2291630406,50.0352915093,609.6 -5.2245179722,50.0350044722,609.6 -5.2249413611,50.0522232222,609.6 -5.2389025278,50.05208019439999,609.6 + + + + +
+ + EGRU004I PREDANNACK RWY 36 + 495707N 0051321W -
495706N 0051411W -
495808N 0051413W thence anti-clockwise by the arc of a circle radius 2 NM centred on 500007N 0051354W to
495809N 0051322W -
495707N 0051321W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.2224781111,49.9518661389,609.6 -5.2229034722,49.9692269444,609.6 -5.2275257288,49.9688452124,609.6 -5.2321824878,49.9687336718,609.6 -5.2368358889,49.96889322219999,609.6 -5.23641025,49.9517231111,609.6 -5.2224781111,49.9518661389,609.6 + + + + +
+ + EGRU005A NEWQUAY + A circle, 2.5 NM radius, centred at 502627N 0045943W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.995375,50.4823974866,609.6 -5.0013939644,50.4822197775,609.6 -5.0073614427,50.4816881703,609.6 -5.0132263927,50.4808072122,609.6 -5.0189386559,50.4795844382,609.6 -5.0244493897,50.47803030640001,609.6 -5.0297114877,50.47615810770001,609.6 -5.0346799846,50.4739838514,609.6 -5.0393124424,50.47152612730001,609.6 -5.0435693141,50.4688059458,609.6 -5.0474142818,50.4658465572,609.6 -5.0508145666,50.462673252,609.6 -5.0537412075,50.4593131434,609.6 -5.0561693067,50.4557949349,609.6 -5.0580782394,50.4521486742,609.6 -5.0594518272,50.44840549540001,609.6 -5.0602784716,50.4445973531,609.6 -5.0605512498,50.4407567484,609.6 -5.0602679685,50.4369164519,609.6 -5.0594311786,50.43310922370001,609.6 -5.0580481486,50.4293675339,609.6 -5.0561307983,50.4257232862,609.6 -5.0536955929,50.4222075464,609.6 -5.0507633991,50.4188502779,609.6 -5.0473593039,50.4156800876,609.6 -5.043512398,50.41272398260001,609.6 -5.0392555263,50.4100071416,609.6 -5.0346250067,50.40755270109999,609.6 -5.0296603202,50.40538155969999,609.6 -5.024403775,50.4035122011,609.6 -5.0189001474,50.401960538,609.6 -5.0131963018,50.4007397771,609.6 -5.0073407941,50.3998603079,609.6 -5.0013834612,50.39932961489999,609.6 -4.995375,50.39915221399999,609.6 -4.9893665388,50.39932961489999,609.6 -4.9834092059,50.3998603079,609.6 -4.9775536982,50.4007397771,609.6 -4.9718498526,50.401960538,609.6 -4.966346225,50.4035122011,609.6 -4.9610896798,50.40538155969999,609.6 -4.9561249933,50.40755270109999,609.6 -4.9514944737,50.4100071416,609.6 -4.947237602,50.41272398260001,609.6 -4.9433906961,50.4156800876,609.6 -4.9399866009,50.4188502779,609.6 -4.9370544071,50.4222075464,609.6 -4.9346192017,50.4257232862,609.6 -4.9327018514,50.4293675339,609.6 -4.9313188214,50.43310922370001,609.6 -4.9304820315,50.4369164519,609.6 -4.9301987502,50.4407567484,609.6 -4.9304715284,50.4445973531,609.6 -4.9312981728,50.44840549540001,609.6 -4.9326717606,50.4521486742,609.6 -4.9345806933,50.4557949349,609.6 -4.9370087925,50.4593131434,609.6 -4.9399354334,50.462673252,609.6 -4.9433357182,50.4658465572,609.6 -4.9471806859,50.4688059458,609.6 -4.9514375576,50.47152612730001,609.6 -4.9560700154,50.4739838514,609.6 -4.9610385123,50.47615810770001,609.6 -4.9663006103,50.47803030640001,609.6 -4.9718113441,50.4795844382,609.6 -4.9775236073,50.4808072122,609.6 -4.9833885573,50.4816881703,609.6 -4.9893560356,50.4822197775,609.6 -4.995375,50.4823974866,609.6 + + + + +
+ + EGRU005B NEWQUAY RWY 12 + 502758N 0050435W -
502825N 0050409W -
502756N 0050252W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to
502728N 0050317W -
502758N 0050435W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0762666667,50.46597222219999,609.6 -5.0547863333,50.4579050556,609.6 -5.0526992207,50.4605952669,609.6 -5.0503135172,50.4631823971,609.6 -5.0476416111,50.4656529722,609.6 -5.0691111111,50.4737166667,609.6 -5.0762666667,50.46597222219999,609.6 + + + + +
+ + EGRU005C NEWQUAY RWY 30 + 502501N 0045506W -
502433N 0045531W -
502457N 0045635W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 502627N 0045943W to
502525N 0045610W -
502501N 0045506W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9182166667,50.4169,609.6 -4.9360059167,50.4236155278,609.6 -4.9380977536,50.4209275579,609.6 -4.9404871378,50.41834285089999,609.6 -4.9431616111,50.4158748333,609.6 -4.9253611111,50.4091555556,609.6 -4.9182166667,50.4169,609.6 + + + + +
+ + EGRU006A EXETER + A circle, 2.5 NM radius, centred at 504403N 0032450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4138111111,50.7759120447,609.6 -3.4198676675,50.775734343,609.6 -3.4258724149,50.77520275789999,609.6 -3.4317739908,50.7743218365,609.6 -3.4375219223,50.7730991138,609.6 -3.4430670607,50.7715450477,609.6 -3.4483620045,50.7696729288,609.6 -3.4533615069,50.7674987661,609.6 -3.4580228647,50.76504114909999,609.6 -3.4623062837,50.7623210878,609.6 -3.4661752198,50.7593618318,609.6 -3.4695966899,50.7561886708,609.6 -3.4725415531,50.75282871739999,609.6 -3.4749847572,50.7493106742,609.6 -3.4769055504,50.7456645876,609.6 -3.4782876544,50.74192159060001,609.6 -3.4791194006,50.7381136364,609.6 -3.4793938246,50.7342732247,609.6 -3.479108721299999,50.7304331244,609.6 -3.4782666594,50.726626094,609.6 -3.4768749545,50.72288460170001,609.6 -3.4749456026,50.7192405493,609.6 -3.4724951729,50.7157250007,609.6 -3.4695446637,50.71236791740001,609.6 -3.4661193192,50.7091979042,609.6 -3.4622484124,50.7062419664,609.6 -3.4579649933,50.7035252806,609.6 -3.4533056062,50.70107098179999,609.6 -3.448309978200001,50.6988999669,609.6 -3.4430206805,50.6970307181,609.6 -3.4374827676,50.69547914659999,609.6 -3.4317433949,50.6942584582,609.6 -3.425851419799999,50.6933790415,609.6 -3.4198569881,50.6928483801,609.6 -3.4138111111,50.6926709899,609.6 -3.407765234100001,50.6928483801,609.6 -3.4017708025,50.6933790415,609.6 -3.3958788273,50.6942584582,609.6 -3.3901394546,50.69547914659999,609.6 -3.3846015417,50.6970307181,609.6 -3.379312244,50.6988999669,609.6 -3.374316616,50.70107098179999,609.6 -3.3696572289,50.7035252806,609.6 -3.3653738098,50.7062419664,609.6 -3.361502903,50.7091979042,609.6 -3.358077558499999,50.71236791740001,609.6 -3.3551270493,50.7157250007,609.6 -3.3526766197,50.7192405493,609.6 -3.3507472677,50.72288460170001,609.6 -3.3493555629,50.726626094,609.6 -3.348513501,50.7304331244,609.6 -3.3482283977,50.7342732247,609.6 -3.3485028216,50.7381136364,609.6 -3.3493345678,50.74192159060001,609.6 -3.3507166719,50.7456645876,609.6 -3.352637465,50.7493106742,609.6 -3.3550806691,50.75282871739999,609.6 -3.3580255323,50.7561886708,609.6 -3.3614470024,50.7593618318,609.6 -3.365315938500001,50.7623210878,609.6 -3.3695993576,50.76504114909999,609.6 -3.3742607153,50.7674987661,609.6 -3.3792602178,50.7696729288,609.6 -3.3845551615,50.7715450477,609.6 -3.3901002999,50.7730991138,609.6 -3.3958482314,50.7743218365,609.6 -3.4017498073,50.77520275789999,609.6 -3.4077545547,50.775734343,609.6 -3.4138111111,50.7759120447,609.6 + + + + +
+ + EGRU006B EXETER RWY 08 + 504301N 0032942W -
504332N 0032954W -
504343N 0032844W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to
504312N 0032831W -
504301N 0032942W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.495058333299999,50.7169166667,609.6 -3.4754004444,50.7200062778,609.6 -3.476864009799999,50.7228603054,609.6 -3.4779999174,50.72577385219999,609.6 -3.4788021944,50.7287317778,609.6 -3.4984444444,50.7256444444,609.6 -3.495058333299999,50.7169166667,609.6 + + + + +
+ + EGRU006C EXETER RWY 26 + 504506N 0031958W -
504434N 0031946W -
504423N 0032056W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504403N 0032450W to
504455N 0032108W -
504506N 0031958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3329055556,50.7515472222,609.6 -3.3521841667,50.7485441667,609.6 -3.3507272916,50.7456883341,609.6 -3.3495987816,50.7427732951,609.6 -3.3488044444,50.7398142222,609.6 -3.3295111111,50.74281944440001,609.6 -3.3329055556,50.7515472222,609.6 + + + + +
+ + EGRU007A DUNKESWELL + A circle, 2 NM radius, centred at 505136N 0031405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.234722222199999,50.8932956049,609.6 -3.2401351738,50.8931190092,609.6 -3.2454906252,50.8925910977,609.6 -3.2507316905,50.89171747819999,609.6 -3.2558027069,50.8905074303,609.6 -3.260649828400001,50.888973806,609.6 -3.2652216011,50.8871328929,609.6 -3.269469511400001,50.8850042399,609.6 -3.2733485023,50.88261044859999,609.6 -3.2768174528,50.8799769321,609.6 -3.279839613,50.877131644,609.6 -3.2823829938,50.8741047808,609.6 -3.284420702899999,50.8709284596,609.6 -3.2859312278,50.8676363769,609.6 -3.2868986599,50.8642634502,609.6 -3.2873128583,50.8608454468,609.6 -3.2871695533,50.85741860420001,609.6 -3.2864703856,50.8540192458,609.6 -3.2852228848,50.8506833957,609.6 -3.2834403834,50.8474463977,609.6 -3.2811418721,50.8443425409,609.6 -3.2783517935,50.84140469750001,609.6 -3.275099780300001,50.8386639756,609.6 -3.2714203384,50.8361493907,609.6 -3.2673524801,50.8338875599,609.6 -3.2629393099,50.8319024213,609.6 -3.2582275683,50.83021498160001,609.6 -3.253267138,50.8288430954,609.6 -3.2481105182,50.82780127699999,609.6 -3.2428122708,50.8271005476,609.6 -3.237428447,50.82674832000001,609.6 -3.2320159975,50.82674832000001,609.6 -3.2266321737,50.8271005476,609.6 -3.2213339263,50.82780127699999,609.6 -3.2161773064,50.8288430954,609.6 -3.2112168762,50.83021498160001,609.6 -3.2065051345,50.8319024213,609.6 -3.2020919643,50.8338875599,609.6 -3.198024106,50.8361493907,609.6 -3.1943446642,50.8386639756,609.6 -3.1910926509,50.84140469750001,609.6 -3.1883025723,50.8443425409,609.6 -3.186004061,50.8474463977,609.6 -3.1842215597,50.8506833957,609.6 -3.182974058800001,50.8540192458,609.6 -3.1822748912,50.85741860420001,609.6 -3.1821315861,50.8608454468,609.6 -3.1825457846,50.8642634502,609.6 -3.1835132166,50.8676363769,609.6 -3.185023741599999,50.8709284596,609.6 -3.1870614507,50.8741047808,609.6 -3.1896048314,50.877131644,609.6 -3.192626991700001,50.8799769321,609.6 -3.196095942099999,50.88261044859999,609.6 -3.1999749331,50.8850042399,609.6 -3.2042228433,50.8871328929,609.6 -3.208794616,50.888973806,609.6 -3.2136417376,50.8905074303,609.6 -3.2187127539,50.89171747819999,609.6 -3.2239538193,50.8925910977,609.6 -3.2293092706,50.8931190092,609.6 -3.234722222199999,50.8932956049,609.6 + + + + +
+ + EGRU007B DUNKESWELL RWY 04 + 504912N 0031650W -
504933N 0031729W -
505017N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to
504956N 0031549W -
504912N 0031650W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.280597222199999,50.81986666669999,609.6 -3.2636403056,50.8321895278,609.6 -3.2674813106,50.8339522696,609.6 -3.2710560959,50.8359269644,609.6 -3.2743355833,50.83809755560001,609.6 -3.2912888889,50.82577499999999,609.6 -3.280597222199999,50.81986666669999,609.6 + + + + +
+ + EGRU007C DUNKESWELL RWY 22 + 505400N 0031120W -
505339N 0031042W -
505255N 0031142W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505136N 0031405W to
505316N 0031221W -
505400N 0031120W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1889333333,50.9000361111,609.6 -3.2058049722,50.88781786109999,609.6 -3.2019593037,50.88605486699999,609.6 -3.198380808500001,50.88407967649999,609.6 -3.195098638899999,50.8819083889,609.6 -3.178222222200001,50.8941277778,609.6 -3.1889333333,50.9000361111,609.6 + + + + +
+ + EGRU008A MERRYFIELD + A circle, 2.5 NM radius, centred at 505747N 0025620W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9388138889,51.0047548483,609.6 -2.944900194300001,51.0045771522,609.6 -2.950934435,51.0040455843,609.6 -2.9568649954,51.00316469140001,609.6 -2.9626411535,51.0019420085,609.6 -2.9682135183,51.00038799330001,609.6 -2.9735344549,50.9985159364,609.6 -2.9785584938,50.9963418465,609.6 -2.9832427217,50.9938843127,609.6 -2.987547149300001,50.9911643446,609.6 -2.9914350528,50.9882051916,609.6 -2.9948732879,50.9850321428,609.6 -2.9978325712,50.98167231010001,609.6 -3.0002877285,50.9781543952,609.6 -3.0022179071,50.974508444,609.6 -3.0036067504,50.9707655884,609.6 -3.0044425336,50.9669577805,609.6 -3.0047182595,50.963117519,609.6 -3.004431714,50.9592775715,609.6 -3.0035854798,50.955470695,609.6 -3.0021869098,50.9517293565,609.6 -3.000248060000001,50.94808545630001,609.6 -2.997785582400001,50.94457005659999,609.6 -2.9948205789,50.9412131175,609.6 -2.9913784186,50.93804324229999,609.6 -2.9874885185,50.9350874347,609.6 -2.983184091,50.93237087,609.6 -2.9785018596,50.9299166817,609.6 -2.9734817459,50.9277457654,609.6 -2.9681665295,50.9258766021,609.6 -2.9626014849,50.9243251021,609.6 -2.956833998,50.9231044702,609.6 -2.9509131644,50.9222250943,609.6 -2.944889374799999,50.9216944577,609.6 -2.9388138889,50.9215170757,609.6 -2.932738403,50.9216944577,609.6 -2.9267146134,50.9222250943,609.6 -2.9207937798,50.9231044702,609.6 -2.9150262928,50.9243251021,609.6 -2.9094612483,50.9258766021,609.6 -2.9041460319,50.9277457654,609.6 -2.8991259182,50.9299166817,609.6 -2.8944436868,50.93237087,609.6 -2.8901392593,50.9350874347,609.6 -2.8862493592,50.93804324229999,609.6 -2.8828071989,50.9412131175,609.6 -2.8798421954,50.94457005659999,609.6 -2.8773797178,50.94808545630001,609.6 -2.875440868,50.9517293565,609.6 -2.874042298,50.955470695,609.6 -2.8731960637,50.9592775715,609.6 -2.872909518200001,50.963117519,609.6 -2.8731852442,50.9669577805,609.6 -2.8740210274,50.9707655884,609.6 -2.8754098707,50.974508444,609.6 -2.8773400493,50.9781543952,609.6 -2.8797952066,50.98167231010001,609.6 -2.8827544899,50.9850321428,609.6 -2.886192725,50.9882051916,609.6 -2.8900806285,50.9911643446,609.6 -2.894385056,50.9938843127,609.6 -2.899069284,50.9963418465,609.6 -2.9040933229,50.9985159364,609.6 -2.9094142595,51.00038799330001,609.6 -2.9149866243,51.0019420085,609.6 -2.9207627824,51.00316469140001,609.6 -2.9266933427,51.0040455843,609.6 -2.9327275835,51.0045771522,609.6 -2.9388138889,51.0047548483,609.6 + + + + +
+ + EGRU008B MERRYFIELD RWY 03 + 505506N 0025754W -
505519N 0025840W -
505540N 0025825W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505526N 0025739W -
505506N 0025754W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9648844444,50.9183033056,609.6 -2.9608878056,50.9239230833,609.6 -2.9653039687,50.9250301094,609.6 -2.9695825808,50.9263353435,609.6 -2.9737014167,50.927832,609.6 -2.9778534167,50.9219914444,609.6 -2.9648844444,50.9183033056,609.6 + + + + +
+ + EGRU008C MERRYFIELD RWY 21 + 510051N 0025444W -
510038N 0025357W -
505958N 0025425W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
510011N 0025512W -
510051N 0025444W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.912232250000001,51.0141108611,609.6 -2.92012775,51.0030484167,609.6 -2.915615938799999,51.0020936564,609.6 -2.911225174100001,51.00093597,609.6 -2.9069783611,50.9995813889,609.6 -2.8992376111,51.0104227778,609.6 -2.912232250000001,51.0141108611,609.6 + + + + +
+ + EGRU008D MERRYFIELD RWY 09 + 505714N 0030118W -
505746N 0030122W -
505750N 0030017W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505718N 0030012W -
505714N 0030118W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0216006389,50.9538749444,609.6 -3.0034171389,50.95492480559999,609.6 -3.004188227499999,50.9578865645,609.6 -3.0046194034,50.9608757179,609.6 -3.0047083611,50.96387672219999,609.6 -3.0228821389,50.9628273889,609.6 -3.0216006389,50.9538749444,609.6 + + + + +
+ + EGRU008E MERRYFIELD RWY 27 + 505820N 0025122W -
505748N 0025117W -
505745N 0025223W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505817N 0025227W -
505820N 0025122W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8560128611,50.9723541944,609.6 -2.8741930833,50.971328,609.6 -2.8734281588,50.9683656014,609.6 -2.8730034372,50.9653760928,609.6 -2.8729210556,50.96237502780001,609.6 -2.8547311111,50.96340175,609.6 -2.8560128611,50.9723541944,609.6 + + + + +
+ + EGRU008F MERRYFIELD RWY 16 + 510036N 0025807W -
510047N 0025718W -
510015N 0025702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
510006N 0025751W -
510036N 0025807W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9685856389,51.01010763890001,609.6 -2.9641047222,51.0015711389,609.6 -2.9596462924,51.0026227467,609.6 -2.9550791053,51.0034685703,609.6 -2.950427,51.0041041944,609.6 -2.9550573333,51.01293025,609.6 -2.9685856389,51.01010763890001,609.6 + + + + +
+ + EGRU008G MERRYFIELD RWY 34 + 505508N 0025421W -
505458N 0025510W -
505522N 0025522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 505747N 0025620W to
505533N 0025434W -
505508N 0025421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9058088333,50.9188734444,609.6 -2.9094674444,50.9258746667,609.6 -2.913795743000001,50.9246351369,609.6 -2.9182540045,50.9235959522,609.6 -2.922819055600001,50.9227625,609.6 -2.9193098333,50.9160507778,609.6 -2.9058088333,50.9188734444,609.6 + + + + +
+ + EGRU009A YEOVIL/WESTLAND + 505817N 0024035W -
505804N 0023747W thence clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to -
505817N 0024035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6762913333,50.97146936109999,609.6 -2.6813214099,50.9701675861,609.6 -2.6861121821,50.9685455593,609.6 -2.6906126594,50.9666205383,609.6 -2.6947749661,50.9644130177,609.6 -2.6985548452,50.9619464963,609.6 -2.7019121291,50.9592472264,609.6 -2.7048111668,50.9563439325,609.6 -2.7072212013,50.9532675051,609.6 -2.7091166941,50.9500506702,609.6 -2.7104775937,50.9467276407,609.6 -2.7112895447,50.9433337517,609.6 -2.7115440354,50.93990508379999,609.6 -2.7112384838,50.93647807970001,609.6 -2.7103762595,50.9330891564,609.6 -2.7089666428,50.9297743184,609.6 -2.7070247211,50.9265687754,609.6 -2.7045712243,50.9235065695,609.6 -2.7016323001,50.9206202139,609.6 -2.6982392335,50.917940349,609.6 -2.694428112,50.91549541799999,609.6 -2.690239441,50.9133113666,609.6 -2.685717713,50.9114113683,609.6 -2.6809109363,50.90981558049999,609.6 -2.6758701262,50.908540931,609.6 -2.6706487661,50.9076009399,609.6 -2.6653022429,50.9070055769,609.6 -2.6598872626,50.9067611562,609.6 -2.6544612525,50.90687027,609.6 -2.6490817564,50.907331761,609.6 -2.6438058276,50.908140735,609.6 -2.6386894283,50.9092886121,609.6 -2.6337868387,50.91076321700001,609.6 -2.6291500848,50.91254890809999,609.6 -2.6248283884,50.91462674169999,609.6 -2.6208676465,50.9169746722,609.6 -2.6173099448,50.9195677849,609.6 -2.614193111,50.922378559,609.6 -2.6115503118,50.9253771585,609.6 -2.6094096989,50.928531748,609.6 -2.6077941069,50.9318088292,609.6 -2.6067208071,50.9351735959,609.6 -2.6062013196,50.93859030339999,609.6 -2.6062412861,50.9420226471,609.6 -2.6068404051,50.9454341484,609.6 -2.6079924294,50.9487885423,609.6 -2.6096852278,50.9520501632,609.6 -2.6119009088,50.95518432450001,609.6 -2.6146160072,50.9581576886,609.6 -2.6178017294,50.9609386219,609.6 -2.6214242569,50.96349753249999,609.6 -2.6254451044,50.9658071869,609.6 -2.6298215278,50.96784299999999,609.6 -2.6762913333,50.97146936109999,609.6 + + + + +
+ + EGRU009B YEOVIL/WESTLAND RWY 09 + 505614N 0024415W -
505646N 0024414W -
505644N 0024239W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to
505612N 0024241W -
505614N 0024415W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7375611111,50.93712777779999,609.6 -2.7112603056,50.9366077222,609.6 -2.7115396944,50.9396068368,609.6 -2.7113901,50.9426096531,609.6 -2.7108126389,50.9455917222,609.6 -2.7371027778,50.9461111111,609.6 -2.7375611111,50.93712777779999,609.6 + + + + +
+ + EGRU009C YEOVIL/WESTLAND RWY 27 + 505635N 0023449W -
505602N 0023450W -
505604N 0023625W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505624N 0023932W to
505636N 0023623W -
505635N 0023449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5801416667,50.9429222222,609.6 -2.6064268056,50.9434709722,609.6 -2.6061537863,50.9404710151,609.6 -2.6063099945,50.9374677222,609.6 -2.6068940556,50.93448555560001,609.6 -2.5805972222,50.9339361111,609.6 -2.5801416667,50.9429222222,609.6 + + + + +
+ + EGRU010A COMPTON ABBAS + A circle, 2 NM radius, centred at 505802N 0020913W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1536111111,51.0005172124,609.6 -2.1590365291,51.00034061940001,609.6 -2.1644043138,50.9998127162,609.6 -2.1696574483,50.9989391106,609.6 -2.1747401408,50.9977290819,609.6 -2.1795984212,50.9961954822,609.6 -2.1841807168,50.9943545989,609.6 -2.1884384021,50.9922259806,609.6 -2.1923263164,50.9898322288,609.6 -2.1958032439,50.98719875640001,609.6 -2.1988323506,50.98435351660001,609.6 -2.2013815737,50.9813267053,609.6 -2.2034239597,50.9781504395,609.6 -2.2049379469,50.9748584151,609.6 -2.2059075905,50.9714855491,609.6 -2.2063227271,50.9680676081,609.6 -2.2061790777,50.964640829,609.6 -2.2054782875,50.96124153460001,609.6 -2.2042279037,50.9579057482,609.6 -2.2024412905,50.9546688129,609.6 -2.2001374823,50.95156501700001,609.6 -2.1973409787,50.948627232,609.6 -2.1940814806,50.9458865651,609.6 -2.1903935737,50.9433720314,609.6 -2.1863163598,50.941110247,609.6 -2.1818930427,50.9391251494,609.6 -2.1771704701,50.9374377449,609.6 -2.1721986392,50.9360658874,609.6 -2.1670301693,50.9350240909,609.6 -2.1617197477,50.9343233764,609.6 -2.1563235537,50.93397115619999,609.6 -2.1508986685,50.93397115619999,609.6 -2.1455024745,50.9343233764,609.6 -2.1401920529,50.9350240909,609.6 -2.135023583,50.9360658874,609.6 -2.1300517522,50.9374377449,609.6 -2.1253291795,50.9391251494,609.6 -2.1209058624,50.941110247,609.6 -2.1168286486,50.9433720314,609.6 -2.1131407416,50.9458865651,609.6 -2.1098812435,50.948627232,609.6 -2.1070847399,50.95156501700001,609.6 -2.1047809318,50.9546688129,609.6 -2.1029943185,50.9579057482,609.6 -2.1017439347,50.96124153460001,609.6 -2.1010431445,50.964640829,609.6 -2.1008994951,50.9680676081,609.6 -2.1013146317,50.9714855491,609.6 -2.1022842754,50.9748584151,609.6 -2.1037982626,50.9781504395,609.6 -2.1058406485,50.9813267053,609.6 -2.1083898716,50.98435351660001,609.6 -2.1114189783,50.98719875640001,609.6 -2.1148959058,50.9898322288,609.6 -2.1187838201,50.9922259806,609.6 -2.1230415054,50.9943545989,609.6 -2.127623801,50.9961954822,609.6 -2.1324820814,50.9977290819,609.6 -2.137564774,50.9989391106,609.6 -2.1428179084,50.9998127162,609.6 -2.1481856932,51.00034061940001,609.6 -2.1536111111,51.0005172124,609.6 + + + + +
+ + EGRU010B COMPTON ABBAS RWY 08 + 505708N 0021337W -
505739N 0021349W -
505752N 0021222W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to
505720N 0021211W -
505708N 0021337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2270083333,50.9520972222,609.6 -2.2029971944,50.9555675556,609.6 -2.2044610998,50.9584260794,609.6 -2.2055112153,50.9613562969,609.6 -2.2061389167,50.9643343611,609.6 -2.2301694444,50.9608611111,609.6 -2.2270083333,50.9520972222,609.6 + + + + +
+ + EGRU010C COMPTON ABBAS RWY 26 + 505857N 0020449W -
505825N 0020438W -
505813N 0020604W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505802N 0020913W to
505844N 0020615W -
505857N 0020449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0802805556,50.9824361111,609.6 -2.1042831944,50.97899544440001,609.6 -2.1028044889,50.9761396879,609.6 -2.1017397236,50.9732113938,609.6 -2.1010975,50.9702344167,609.6 -2.0771138889,50.97367222220001,609.6 -2.0802805556,50.9824361111,609.6 + + + + +
+ + EGRU011A BOURNEMOUTH + A circle, 2.5 NM radius, centred at 504648N 0015033W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8425138889,50.8216839385,609.6 -1.8485763644,50.8215062379,609.6 -1.8545869801,50.82097465619999,609.6 -1.860494323,50.8200937406,609.6 -1.8662478708,50.8188710258,609.6 -1.8717984264,50.8173169699,609.6 -1.8770985419,50.81544486349999,609.6 -1.8821029264,50.8132707154,609.6 -1.8867688346,50.810813115,609.6 -1.8910564338,50.8080930724,609.6 -1.8949291438,50.805133837,609.6 -1.8983539496,50.8019606985,609.6 -1.901301682,50.7986007693,609.6 -1.9037472645,50.79508275180001,609.6 -1.9056699251,50.7914366922,609.6 -1.9070533701,50.7876937236,609.6 -1.9078859195,50.7838857986,609.6 -1.9081606025,50.780045417,609.6 -1.9078752123,50.77620534730001,609.6 -1.9070323202,50.7723983477,609.6 -1.9056392495,50.76865688609999,609.6 -1.9037080077,50.7650128642,609.6 -1.9012551809,50.7614973454,609.6 -1.8983017878,50.758140291,609.6 -1.8948730975,50.75497030530001,609.6 -1.8909984115,50.75201439360001,609.6 -1.8867108124,50.7492977321,609.6 -1.88204688,50.7468434554,609.6 -1.87704638,50.74467246020001,609.6 -1.8717519253,50.7428032284,609.6 -1.866208614,50.7412516713,609.6 -1.8604636474,50.7400309942,609.6 -1.8545659302,50.7391515856,609.6 -1.8485656572,50.73862092920001,609.6 -1.8425138889,50.7384435406,609.6 -1.8364621206,50.73862092920001,609.6 -1.8304618475,50.7391515856,609.6 -1.8245641304,50.7400309942,609.6 -1.8188191638,50.7412516713,609.6 -1.8132758525,50.7428032284,609.6 -1.8079813978,50.74467246020001,609.6 -1.8029808978,50.7468434554,609.6 -1.7983169654,50.7492977321,609.6 -1.7940293662,50.75201439360001,609.6 -1.7901546803,50.75497030530001,609.6 -1.78672599,50.758140291,609.6 -1.7837725969,50.7614973454,609.6 -1.78131977,50.7650128642,609.6 -1.7793885283,50.76865688609999,609.6 -1.7779954575,50.7723983477,609.6 -1.7771525655,50.77620534730001,609.6 -1.7768671752,50.780045417,609.6 -1.7771418583,50.7838857986,609.6 -1.7779744077,50.7876937236,609.6 -1.7793578527,50.7914366922,609.6 -1.7812805133,50.79508275180001,609.6 -1.7837260958,50.7986007693,609.6 -1.7866738282,50.8019606985,609.6 -1.790098634,50.805133837,609.6 -1.793971344,50.8080930724,609.6 -1.7982589432,50.810813115,609.6 -1.8029248514,50.8132707154,609.6 -1.8079292359,50.81544486349999,609.6 -1.8132293514,50.8173169699,609.6 -1.818779907,50.8188710258,609.6 -1.8245334547,50.8200937406,609.6 -1.8304407977,50.82097465619999,609.6 -1.8364514133,50.8215062379,609.6 -1.8425138889,50.8216839385,609.6 + + + + +
+ + EGRU011B BOURNEMOUTH RWY 08 + 504546N 0015508W -
504617N 0015521W -
504626N 0015427W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to
504555N 0015414W -
504546N 0015508W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9189138889,50.7626972222,609.6 -1.9038303611,50.7652141944,609.6 -1.9053602225,50.768054234,609.6 -1.906563561,50.7709567886,609.6 -1.9074340556,50.7739067778,609.6 -1.9225055556,50.7713916667,609.6 -1.9189138889,50.7626972222,609.6 + + + + +
+ + EGRU011C BOURNEMOUTH RWY 26 + 504754N 0014536W -
504723N 0014523W -
504710N 0014639W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 504648N 0015033W to
504742N 0014652W -
504754N 0014536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7601111111,50.798375,609.6 -1.7811646111,50.79489127780001,609.6 -1.7796401409,50.7920496202,609.6 -1.7784428843,50.7891457046,609.6 -1.7775790278,50.7861946389,609.6 -1.7565111111,50.7896805556,609.6 -1.7601111111,50.798375,609.6 + + + + +
+ + EGRU012A SOUTHAMPTON + A circle, 2 NM radius, centred at 505701N 0012124W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3566666667,50.9835728651,609.6 -1.3620901095,50.9833962716,609.6 -1.3674559401,50.9828683672,609.6 -1.3727071623,50.98199475929999,609.6 -1.3777880049,50.98078472760001,609.6 -1.3826445173,50.97925112400001,609.6 -1.3872251457,50.977410236,609.6 -1.3914812822,50.97528161220001,609.6 -1.3953677827,50.9728878542,609.6 -1.3988434463,50.97025437479999,609.6 -1.4018714524,50.9674091274,609.6 -1.4044197499,50.9643823079,609.6 -1.4064613948,50.9612060334,609.6 -1.4079748335,50.9579139998,609.6 -1.4089441267,50.9545411242,609.6 -1.4093591147,50.9511231733,609.6 -1.4092155198,50.94769638419999,609.6 -1.4085149867,50.9442970796,609.6 -1.4072650597,50.9409612832,609.6 -1.4054790979,50.937724338,609.6 -1.403176129,50.9346205324,609.6 -1.4003806434,50.9316827382,609.6 -1.3971223312,50.9289420627,609.6 -1.3934357654,50.9264275208,609.6 -1.3893600339,50.9241657291,609.6 -1.3849383244,50.9221806251,609.6 -1.3802174678,50.92049321499999,609.6 -1.3752474433,50.91912135299999,609.6 -1.3700808509,50.918079553,609.6 -1.3647723582,50.91737883609999,609.6 -1.3593781241,50.9170266148,609.6 -1.3539552092,50.9170266148,609.6 -1.3485609751,50.91737883609999,609.6 -1.3432524824,50.918079553,609.6 -1.3380858901,50.91912135299999,609.6 -1.3331158655,50.92049321499999,609.6 -1.3283950089,50.9221806251,609.6 -1.3239732994,50.9241657291,609.6 -1.3198975679,50.9264275208,609.6 -1.3162110021,50.9289420627,609.6 -1.31295269,50.9316827382,609.6 -1.3101572043,50.9346205324,609.6 -1.3078542354,50.937724338,609.6 -1.3060682736,50.9409612832,609.6 -1.3048183467,50.9442970796,609.6 -1.3041178135,50.94769638419999,609.6 -1.3039742186,50.9511231733,609.6 -1.3043892067,50.9545411242,609.6 -1.3053584999,50.9579139998,609.6 -1.3068719385,50.9612060334,609.6 -1.3089135835,50.9643823079,609.6 -1.3114618809,50.9674091274,609.6 -1.314489887,50.97025437479999,609.6 -1.3179655506,50.9728878542,609.6 -1.3218520511,50.97528161220001,609.6 -1.3261081877,50.977410236,609.6 -1.330688816,50.97925112400001,609.6 -1.3355453284,50.98078472760001,609.6 -1.340626171,50.98199475929999,609.6 -1.3458773932,50.9828683672,609.6 -1.3512432239,50.9833962716,609.6 -1.3566666667,50.9835728651,609.6 + + + + +
+ + EGRU012B SOUTHAMPTON RWY 02 + 505359N 0012239W -
505410N 0012327W -
505514N 0012251W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to
505504N 0012203W -
505359N 0012239W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3774111111,50.8996805556,609.6 -1.3674003333,50.9176806667,609.6 -1.3720051772,50.9184244585,609.6 -1.3764853887,50.9194274358,609.6 -1.3808045556,50.9206814444,609.6 -1.3908194444,50.9026638889,609.6 -1.3774111111,50.8996805556,609.6 + + + + +
+ + EGRU012C SOUTHAMPTON RWY 20 + 510004N 0012010W -
505953N 0011921W -
505848N 0011958W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505701N 0012124W to
505858N 0012046W -
510004N 0012010W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3360194444,51.00107222220001,609.6 -1.3461549722,50.9829045278,609.6 -1.3415383674,50.982173002,609.6 -1.3370452143,50.9811815632,609.6 -1.3327121667,50.9799383056,609.6 -1.3225805556,50.99808888889999,609.6 -1.3360194444,51.00107222220001,609.6 + + + + +
+ + EGRU013A LEE-ON-SOLENT + 504810N 0010930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
504824N 0010921W -
505049N 0011117W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -
504810N 0010930W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1582839167,50.8028401667,609.6 -1.1571086989,50.80475837249999,609.6 -1.1558333333,50.8066666667,609.6 -1.1880555556,50.8469444444,609.6 -1.1932506097,50.8479990642,609.6 -1.1985905574,50.8487067777,609.6 -1.2040177313,50.84905994170001,609.6 -1.2094735156,50.8490547418,609.6 -1.2148989838,50.8486912341,609.6 -1.220235539,50.8479733448,609.6 -1.2254255503,50.84690882699999,609.6 -1.2304129795,50.845509177,609.6 -1.235143989,50.84378950919999,609.6 -1.2395675256,50.84176839159999,609.6 -1.2436358739,50.83946764480001,609.6 -1.2473051718,50.8369121049,609.6 -1.250535884,50.8341293541,609.6 -1.2532932278,50.831149422,609.6 -1.2555475458,50.82800446,609.6 -1.2572746236,50.8247283936,609.6 -1.2584559467,50.8213565552,609.6 -1.259078896,50.8179253026,609.6 -1.2591368788,50.8144716262,609.6 -1.2586293949,50.8110327501,609.6 -1.2575620362,50.8076457307,609.6 -1.2559464215,50.8043470578,609.6 -1.2538000663,50.8011722618,609.6 -1.2511461895,50.7981555319,609.6 -1.2480134597,50.79532934869999,609.6 -1.244435683,50.7927241356,609.6 -1.2404514373,50.7903679324,609.6 -1.2361036556,50.788286095,609.6 -1.2314391635,50.7865010235,609.6 -1.2265081763,50.7850319225,609.6 -1.2213637601,50.78389459569999,609.6 -1.2160612632,50.78310127679999,609.6 -1.210657724,50.7826604986,609.6 -1.2052112607,50.7825770017,609.6 -1.1997804503,50.78285168429999,609.6 -1.1944237025,50.78348159200001,609.6 -1.1891986355,50.7844599498,609.6 -1.1841614599,50.7857762344,609.6 -1.1793663774,50.7874162864,609.6 -1.1748650004,50.7893624625,609.6 -1.1707057986,50.7915938234,609.6 -1.1669335786,50.7940863583,609.6 -1.1635890021,50.7968132421,609.6 -1.1607081469,50.7997451229,609.6 -1.1582839167,50.8028401667,609.6 + + + + +
+ + EGRU013B LEE-ON-SOLENT RWY 05 + 504641N 0011523W -
504704N 0011559W -
504744N 0011455W thence anti-clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
504721N 0011419W -
504641N 0011523W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2564055556,50.7780111111,609.6 -1.2384847222,50.7892997778,609.6 -1.2421148936,50.7912314979,609.6 -1.2454559012,50.793362658,609.6 -1.2484805278,50.79567594440001,609.6 -1.2663916667,50.7843916667,609.6 -1.2564055556,50.7780111111,609.6 + + + + +
+ + EGRU013C LEE-ON-SOLENT RWY 23 + 505115N 0010919W -
505052N 0010843W -
504947N 0011027W -
505017N 0011052W -
505115N 0010919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1553555556,50.85421388890001,609.6 -1.1809916111,50.83812125,609.6 -1.1742489167,50.82969575,609.6 -1.1453527778,50.8478333333,609.6 -1.1553555556,50.85421388890001,609.6 + + + + +
+ + EGRU014A FLEETLANDS + 504810N 0010929W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505007N 0011010W to
505054N 0011304W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to
505049N 0011117W -
504824N 0010921W thence clockwise by the arc of a circle radius 2 NM centred on 504857N 0011224W to -
504810N 0010929W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1581221111,50.80279661109999,609.6 -1.1529473377,50.8036983648,609.6 -1.1479446644,50.8049300154,609.6 -1.1431662976,50.8064787134,609.6 -1.1386621169,50.8083283002,609.6 -1.1344791567,50.8104594759,609.6 -1.1306611169,50.8128499992,609.6 -1.1272479066,50.8154749189,609.6 -1.1242752277,50.818306833,609.6 -1.1217742,50.8213161733,609.6 -1.1197710347,50.8244715133,609.6 -1.118286757,50.82773989559999,609.6 -1.1173369832,50.831087175,609.6 -1.1169317532,50.83447837470001,609.6 -1.1170754206,50.8378780514,609.6 -1.1177666027,50.8412506657,609.6 -1.1189981896,50.8445609533,609.6 -1.120757414,50.8477742946,609.6 -1.12302598,50.8508570765,609.6 -1.1257802508,50.8537770454,609.6 -1.1289914919,50.8565036455,609.6 -1.1326261697,50.85900833899999,609.6 -1.1366463005,50.86126490660001,609.6 -1.1410098467,50.8632497227,609.6 -1.1456711573,50.8649420041,609.6 -1.1505814465,50.8663240286,609.6 -1.1556893061,50.867381322,609.6 -1.1609412463,50.8681028098,609.6 -1.1662822588,50.8684809347,609.6 -1.1716563965,50.8685117359,609.6 -1.177007363,50.8681948906,609.6 -1.1822791063,50.8675337178,609.6 -1.1874164094,50.8665351432,609.6 -1.1923654723,50.8652096263,609.6 -1.1970744782,50.8635710497,609.6 -1.201494139,50.8616365735,609.6 -1.2055782131,50.8594264543,609.6 -1.2092839904,50.85696383180001,609.6 -1.2125727394,50.8542744858,609.6 -1.2154101121,50.85138656489999,609.6 -1.2177777778,50.8483333333,609.6 -1.212811389,50.8488638569,609.6 -1.2077876194,50.84909162350001,609.6 -1.2027524466,50.84901454840001,609.6 -1.1977519533,50.8486333371,609.6 -1.1928319027,50.84795147850001,609.6 -1.1880555556,50.8469444444,609.6 -1.1558333333,50.8066666667,609.6 -1.1568187649,50.8046934234,609.6 -1.1581221111,50.80279661109999,609.6 + + + + +
+ + EGRU015A CHICHESTER/GOODWOOD + A circle, 2 NM radius, centred at 505134N 0004533W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7592222222,50.8926428309,609.6 -0.7646350982000001,50.8924662351,609.6 -0.7699904746,50.8919383236,609.6 -0.7752314666999999,50.891064704,609.6 -0.7803024122,50.889854656,609.6 -0.7851494661,50.8883210315,609.6 -0.7897211749000002,50.8864801183,609.6 -0.7939690258000001,50.884351465,609.6 -0.7978479626,50.8819576735,609.6 -0.8013168646000001,50.8793241567,609.6 -0.8043389826999999,50.8764788684,609.6 -0.806882328,50.87345200480001,609.6 -0.8089200087,50.87027568330001,609.6 -0.8104305127,50.8669836003,609.6 -0.8113979313,50.8636106732,609.6 -0.8118121241,50.86019266939999,609.6 -0.8116688211,50.8567658264,609.6 -0.8109696633000001,50.8533664676,609.6 -0.8097221798999999,50.8500306172,609.6 -0.8079397036,50.84679361879999,609.6 -0.8056412243999999,50.8436897616,609.6 -0.8028511848,50.84075191780001,609.6 -0.799599217,50.8380111956,609.6 -0.7959198265,50.8354966104,609.6 -0.7918520250000001,50.83323477929999,609.6 -0.7874389163,50.8312496404,609.6 -0.7827272403999999,50.8295622006,609.6 -0.7777668794,50.8281903142,609.6 -0.7726103315000001,50.8271484956,609.6 -0.767312158,50.8264477661,609.6 -0.7619284093000001,50.8260955385,609.6 -0.7565160352,50.8260955385,609.6 -0.7511322865,50.8264477661,609.6 -0.745834113,50.8271484956,609.6 -0.740677565,50.8281903142,609.6 -0.7357172039999998,50.8295622006,609.6 -0.7310055280999999,50.8312496404,609.6 -0.7265924195,50.83323477929999,609.6 -0.7225246179999999,50.8354966104,609.6 -0.7188452275000001,50.8380111956,609.6 -0.7155932597000001,50.84075191780001,609.6 -0.7128032201,50.8436897616,609.6 -0.7105047409,50.84679361879999,609.6 -0.7087222645000001,50.8500306172,609.6 -0.7074747810999999,50.8533664676,609.6 -0.7067756233999999,50.8567658264,609.6 -0.7066323204,50.86019266939999,609.6 -0.7070465132,50.8636106732,609.6 -0.7080139317999999,50.8669836003,609.6 -0.7095244357000001,50.87027568330001,609.6 -0.7115621164,50.87345200480001,609.6 -0.7141054617,50.8764788684,609.6 -0.7171275798,50.8793241567,609.6 -0.7205964817999999,50.8819576735,609.6 -0.7244754186,50.884351465,609.6 -0.7287232695,50.8864801183,609.6 -0.7332949784,50.8883210315,609.6 -0.7381420322,50.889854656,609.6 -0.7432129777000001,50.891064704,609.6 -0.7484539698,50.8919383236,609.6 -0.7538093463,50.8924662351,609.6 -0.7592222222,50.8926428309,609.6 + + + + +
+ + EGRU015B CHICHESTER/GOODWOOD RWY 06 + 504950N 0004906W -
505017N 0004934W -
505045N 0004826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505018N 0004800W -
504950N 0004906W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8182694444,50.8306472222,609.6 -0.7998924444,50.83823550000001,609.6 -0.8027345357,50.8406427633,609.6 -0.8052225033,50.84320243789999,609.6 -0.8073360277999999,50.8458936944,609.6 -0.8260138889,50.8381805556,609.6 -0.8182694444,50.8306472222,609.6 + + + + +
+ + EGRU015C CHICHESTER/GOODWOOD RWY 24 + 505327N 0004155W -
505300N 0004127W -
505228N 0004244W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505254N 0004313W -
505327N 0004155W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6984805556,50.89073611109999,609.6 -0.7203087222,50.8817591667,609.6 -0.7172734828999999,50.8794467216,609.6 -0.7145805628,50.8769704557,609.6 -0.7122518611,50.8743505833,609.6 -0.690725,50.8832027778,609.6 -0.6984805556,50.89073611109999,609.6 + + + + +
+ + EGRU015D CHICHESTER/GOODWOOD RWY 10 + 505207N 0005003W -
505239N 0004952W -
505226N 0004824W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505155N 0004840W -
505207N 0005003W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8341805556,50.8686861111,609.6 -0.8109841389,50.86530058329999,609.6 -0.8099217521999998,50.8682414599,609.6 -0.8084429209,50.871109396,609.6 -0.8065597222000001,50.87388083329999,609.6 -0.8309749999999999,50.8774444444,609.6 -0.8341805556,50.8686861111,609.6 + + + + +
+ + EGRU015E CHICHESTER/GOODWOOD RWY 28 + 505121N 0004059W -
505049N 0004110W -
505101N 0004231W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505133N 0004224W -
505121N 0004059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6829166667,50.8557472222,609.6 -0.7066161944,50.85923425,609.6 -0.7068499452,50.8562211947,609.6 -0.7075135291999999,50.8532338934,609.6 -0.7086014166999999,50.8502968611,609.6 -0.6861194443999999,50.84698888889999,609.6 -0.6829166667,50.8557472222,609.6 + + + + +
+ + EGRU015F CHICHESTER/GOODWOOD RWY 14 + 505338N 0004857W -
505359N 0004818W -
505314N 0004717W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505253N 0004755W -
505338N 0004857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8157194443999999,50.8937666667,609.6 -0.7987409722000001,50.8813309167,609.6 -0.7954479730999999,50.88349628200001,609.6 -0.7918594971,50.8854649223,609.6 -0.7880047777999999,50.8872207778,609.6 -0.8049527778,50.8996361111,609.6 -0.8157194443999999,50.8937666667,609.6 + + + + +
+ + EGRU015G CHICHESTER/GOODWOOD RWY 32 + 504930N 0004212W -
504909N 0004250W -
504953N 0004350W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505134N 0004533W to
505014N 0004312W -
504930N 0004212W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7032166666999999,50.8249722222,609.6 -0.7198981944,50.8372372778,609.6 -0.7232070255,50.8350833674,609.6 -0.7268087460000001,50.8331270285,609.6 -0.7306740278,50.8313841667,609.6 -0.7139638889,50.81910000000001,609.6 -0.7032166666999999,50.8249722222,609.6 + + + + +
+ + EGRU016A SHOREHAM + A circle, 2 NM radius, centred at 505008N 0001750W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2972222222,50.86885130069999,609.6 -0.3026323425,50.86867470430001,609.6 -0.3079849926,50.8681467909,609.6 -0.3132233168,50.86727316830001,609.6 -0.3182916812,50.866063116,609.6 -0.3231362684,50.86452948609999,609.6 -0.3277056511,50.8626885662,609.6 -0.3319513412,50.86055990519999,609.6 -0.3358283055,50.8581661049,609.6 -0.3392954441,50.8555325783,609.6 -0.3423160267,50.8526872793,609.6 -0.3448580805,50.8496604042,609.6 -0.3468947274,50.8464840704,609.6 -0.348404466,50.84319197439999,609.6 -0.3493713957,50.83981903390001,609.6 -0.3497853811,50.8364010162,609.6 -0.3496421542,50.83297415920001,609.6 -0.3489433551,50.8295747861,609.6 -0.347696509,50.8262389215,609.6 -0.3459149416,50.82300190920001,609.6 -0.3436176333,50.81989803849999,609.6 -0.340829014,50.8169601818,609.6 -0.3375787007,50.8142194473,609.6 -0.3339011814,50.8117048508,609.6 -0.329835448,50.8094430095,609.6 -0.3254245824,50.8074578615,609.6 -0.3207153007,50.8057704138,609.6 -0.3157574598,50.804398521,609.6 -0.3106035313,50.80335669750001,609.6 -0.305308049,50.8026559648,609.6 -0.2999270348,50.8023037355,609.6 -0.2945174097,50.8023037355,609.6 -0.2891363954,50.8026559648,609.6 -0.2838409131,50.80335669750001,609.6 -0.2786869846,50.804398521,609.6 -0.2737291437,50.8057704138,609.6 -0.2690198621,50.8074578615,609.6 -0.2646089964,50.8094430095,609.6 -0.260543263,50.8117048508,609.6 -0.2568657438,50.8142194473,609.6 -0.2536154305,50.8169601818,609.6 -0.2508268112,50.81989803849999,609.6 -0.2485295029,50.82300190920001,609.6 -0.2467479354,50.8262389215,609.6 -0.2455010893,50.8295747861,609.6 -0.2448022902,50.83297415920001,609.6 -0.2446590634,50.8364010162,609.6 -0.2450730487,50.83981903390001,609.6 -0.2460399785,50.84319197439999,609.6 -0.2475497171,50.8464840704,609.6 -0.249586364,50.8496604042,609.6 -0.2521284177,50.8526872793,609.6 -0.2551490003,50.8555325783,609.6 -0.258616139,50.8581661049,609.6 -0.2624931032,50.86055990519999,609.6 -0.2667387934,50.8626885662,609.6 -0.2713081761,50.86452948609999,609.6 -0.2761527632,50.866063116,609.6 -0.2812211277,50.86727316830001,609.6 -0.2864594519,50.8681467909,609.6 -0.291812102,50.86867470430001,609.6 -0.2972222222,50.86885130069999,609.6 + + + + +
+ + EGRU016B SHOREHAM RWY 02 + 504721N 0001907W -
504733N 0001954W -
504824N 0001923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504812N 0001836W -
504721N 0001907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3185777778,50.78930277780001,609.6 -0.3098738056,50.8032385556,609.6 -0.3144202236,50.8040923247,609.6 -0.3188268489,50.8052022003,609.6 -0.3230578611,50.8065591389,609.6 -0.3317638889,50.7926138889,609.6 -0.3185777778,50.78930277780001,609.6 + + + + +
+ + EGRU016C SHOREHAM RWY 20 + 505257N 0001632W -
505245N 0001544W -
505153N 0001617W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505204N 0001705W -
505257N 0001632W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2755388889,50.8825166667,609.6 -0.2846998611,50.8678939167,609.6 -0.2801439923,50.8670472756,609.6 -0.2757274932,50.86594399400001,609.6 -0.2714863889,50.8645930833,609.6 -0.2623277778,50.87920555560001,609.6 -0.2755388889,50.8825166667,609.6 + + + + +
+ + EGRU016D SHOREHAM RWY 02G + 504726N 0001901W -
504737N 0001949W -
504823N 0001920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504811N 0001833W -
504726N 0001901W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3169555556,50.79042222220001,609.6 -0.3090648333,50.80311575,609.6 -0.3136313441,50.8039237264,609.6 -0.3180645222,50.8049890836,609.6 -0.3223283333,50.8063031667,609.6 -0.3301472222,50.7937194444,609.6 -0.3169555556,50.79042222220001,609.6 + + + + +
+ + EGRU016E SHOREHAM RWY 20G + 505257N 0001630W -
505245N 0001542W -
505152N 0001615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505204N 0001703W -
505257N 0001630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2749555556,50.88238888890001,609.6 -0.2840571944,50.8677914722,609.6 -0.2795191306,50.8669086685,609.6 -0.2751254908,50.8657704377,609.6 -0.2709121111,50.86438605560001,609.6 -0.2617388889,50.8790916667,609.6 -0.2749555556,50.88238888890001,609.6 + + + + +
+ + EGRU016F SHOREHAM RWY 06 + 504834N 0002129W -
504903N 0002152W -
504924N 0002046W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504856N 0002021W -
504834N 0002129W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3579972222,50.8094305556,609.6 -0.3390849167,50.8154169167,609.6 -0.3417847915,50.8178920876,609.6 -0.3441212182,50.82051149739999,609.6 -0.3460750833,50.82325377780001,609.6 -0.3643305555999999,50.817475,609.6 -0.3579972222,50.8094305556,609.6 + + + + +
+ + EGRU016G SHOREHAM RWY 24 + 505136N 0001347W -
505107N 0001324W -
505041N 0001448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505110N 0001508W -
505136N 0001347W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2297,50.8599916667,609.6 -0.2523026944,50.8528699444,609.6 -0.2500184701,50.8502315888,609.6 -0.2481200116,50.8474734479,609.6 -0.2466227778,50.8446180556,609.6 -0.2233611111,50.85194722220001,609.6 -0.2297,50.8599916667,609.6 + + + + +
+ + EGRU016H SHOREHAM RWY 13 + 505137N 0002125W -
505204N 0002056W -
505137N 0001956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
505113N 0002029W -
505137N 0002125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3568833332999999,50.8602972222,609.6 -0.3414891667,50.85353133329999,609.6 -0.3387353645,50.85599701280001,609.6 -0.3356396771,50.8582945513,609.6 -0.3322275556,50.8604050278,609.6 -0.3487722222,50.8676777778,609.6 -0.3568833332999999,50.8602972222,609.6 + + + + +
+ + EGRU016I SHOREHAM RWY 31 + 504851N 0001339W -
504825N 0001408W -
504856N 0001519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 505008N 0001750W to
504924N 0001454W -
504851N 0001339W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2274555556,50.8142416667,609.6 -0.2482630278,50.8234243611,609.6 -0.250200315,50.8206661153,609.6 -0.2525237726,50.8180303055,609.6 -0.2552142778,50.8155385833,609.6 -0.2355555556,50.80686388889999,609.6 -0.2274555556,50.8142416667,609.6 + + + + +
+ + EGRU017A LYDD + A circle, 2 NM radius, centred at 505722N 0005621E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9391499999999999,50.9894700535,609.6 0.9337258699999998,50.98929346020001,609.6 0.9283593595,50.9887655562,609.6 0.9231074720000001,50.9878919491,609.6 0.9180259856999999,50.9866819185,609.6 0.9131688582,50.98514831619999,609.6 0.9085876498,50.98330742980001,609.6 0.9043309744,50.981178808,609.6 0.900443982,50.9787850521,609.6 0.8969678786,50.97615157509999,609.6 0.8939394896,50.9733063304,609.6 0.8913908701,50.97027951379999,609.6 0.8893489674,50.9671032423,609.6 0.8878353379,50.9638112119,609.6 0.8868659227,50.9604383396,609.6 0.886450883,50.95702039220001,609.6 0.8865944969,50.9535936066,609.6 0.8872951194000001,50.9501943055,609.6 0.8885452053000001,50.9468585126,609.6 0.8903313938000001,50.9436215708,609.6 0.8926346547,50.9405177686,609.6 0.8954304945,50.9375799776,609.6 0.8986892193,50.9348393051,609.6 0.9023762517,50.93232476600001,609.6 0.9064524989,50.9300629769,609.6 0.9108747678000001,50.92807787510001,609.6 0.9155962214000001,50.926390467,609.6 0.9205668744000001,50.9250186065,609.6 0.92573412,50.9239768078,609.6 0.9310432837999999,50.9232760917,609.6 0.9364381998,50.9229238708,609.6 0.9418618002,50.9229238708,609.6 0.9472567162000001,50.9232760917,609.6 0.95256588,50.9239768078,609.6 0.9577331255999999,50.9250186065,609.6 0.9627037785999999,50.926390467,609.6 0.9674252321999999,50.92807787510001,609.6 0.9718475011,50.9300629769,609.6 0.9759237482999999,50.93232476600001,609.6 0.9796107807,50.9348393051,609.6 0.9828695055,50.9375799776,609.6 0.9856653453000001,50.9405177686,609.6 0.9879686062,50.9436215708,609.6 0.9897547947000001,50.9468585126,609.6 0.9910048806,50.9501943055,609.6 0.9917055031000001,50.9535936066,609.6 0.991849117,50.95702039220001,609.6 0.9914340773,50.9604383396,609.6 0.9904646620999999,50.9638112119,609.6 0.9889510325999999,50.9671032423,609.6 0.9869091299,50.97027951379999,609.6 0.9843605104000001,50.9733063304,609.6 0.9813321214000001,50.97615157509999,609.6 0.977856018,50.9787850521,609.6 0.9739690256,50.981178808,609.6 0.9697123502,50.98330742980001,609.6 0.9651311417999999,50.98514831619999,609.6 0.9602740143,50.9866819185,609.6 0.9551925279999999,50.9878919491,609.6 0.9499406404999999,50.9887655562,609.6 0.9445741300000001,50.98929346020001,609.6 0.9391499999999999,50.9894700535,609.6 + + + + +
+ + EGRU017B LYDD RWY 03 + 505437N 0005403E -
505454N 0005320E -
505551N 0005418E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to
505534N 0005501E -
505437N 0005403E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9009277778,50.9102333333,609.6 0.9169214722,50.9259866667,609.6 0.9127054288000001,50.92737516899999,609.6 0.9087043515999998,50.9289980997,609.6 0.9049507778,50.93084224999999,609.6 0.8889638889,50.9150916667,609.6 0.9009277778,50.9102333333,609.6 + + + + +
+ + EGRU017C LYDD RWY 21 + 510007N 0005838E -
505949N 0005921E -
505853N 0005824E thence anti-clockwise by the arc of a circle radius 2 NM centred on 505722N 0005621E to
505911N 0005741E -
510007N 0005838E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9771694444000001,51.0018333333,609.6 0.9614053611,50.9863595278,609.6 0.9656253747999999,50.98496937670001,609.6 0.9696293844,50.98334461529999,609.6 0.97338475,50.9814985,609.6 0.9891555556,50.996975,609.6 0.9771694444000001,51.0018333333,609.6 + + + + +
+ + EGRU019A LERWICK/TINGWALL + A circle, 2 NM radius, centred at 601131N 0011437W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2436111111,60.22518927309999,609.6 -1.25048308,60.2250128939,609.6 -1.2572819849,60.2244856317,609.6 -1.2639355456,60.22361309210001,609.6 -1.2703730408,60.2224045513,609.6 -1.2765260659,60.22087285609999,609.6 -1.2823292652,60.2190342866,609.6 -1.2877210302,60.2169083816,609.6 -1.2926441565,60.2145177293,609.6 -1.2970464527,60.2118877258,609.6 -1.3008812932,60.2090463035,609.6 -1.3041081112,60.2060236326,609.6 -1.3066928252,60.20285179940001,609.6 -1.3086081946,60.1995644641,609.6 -1.3098341021,60.19619650240001,609.6 -1.3103577589,60.19278363469999,609.6 -1.3101738317,60.18936204650001,609.6 -1.3092844896,60.1859680046,609.6 -1.3076993726,60.1826374726,609.6 -1.3054354794,60.17940573060001,609.6 -1.30251698,60.176307002,609.6 -1.2989749513,60.1733740921,609.6 -1.2948470426,60.1706380425,609.6 -1.2901770716,60.1681278037,609.6 -1.2850145576,60.1658699305,609.6 -1.2794141959,60.16388830319999,609.6 -1.2734352793,60.162203876,609.6 -1.2671410726,60.16083445780001,609.6 -1.2605981468,60.1597945248,609.6 -1.2538756796,60.1590950691,609.6 -1.2470447298,60.1587434834,609.6 -1.2401774924,60.1587434834,609.6 -1.2333465426,60.1590950691,609.6 -1.2266240754,60.1597945248,609.6 -1.2200811496,60.16083445780001,609.6 -1.2137869429,60.162203876,609.6 -1.2078080264,60.16388830319999,609.6 -1.2022076647,60.1658699305,609.6 -1.1970451506,60.1681278037,609.6 -1.1923751796,60.1706380425,609.6 -1.1882472709,60.1733740921,609.6 -1.1847052422,60.176307002,609.6 -1.1817867428,60.17940573060001,609.6 -1.1795228496,60.1826374726,609.6 -1.1779377326,60.1859680046,609.6 -1.1770483906,60.18936204650001,609.6 -1.1768644633,60.19278363469999,609.6 -1.1773881202,60.19619650240001,609.6 -1.1786140277,60.1995644641,609.6 -1.180529397,60.20285179940001,609.6 -1.183114111,60.2060236326,609.6 -1.1863409291,60.2090463035,609.6 -1.1901757695,60.2118877258,609.6 -1.1945780657,60.2145177293,609.6 -1.1995011921,60.2169083816,609.6 -1.204892957,60.2190342866,609.6 -1.2106961563,60.22087285609999,609.6 -1.2168491815,60.2224045513,609.6 -1.2232866766,60.22361309210001,609.6 -1.2299402373,60.2244856317,609.6 -1.2367391422,60.2250128939,609.6 -1.2436111111,60.22518927309999,609.6 + + + + +
+ + EGRU019B LERWICK/TINGWALL RWY 02 + 600839N 0011524W -
600847N 0011627W -
600939N 0011603W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to
600932N 0011500W -
600839N 0011524W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2567777778,60.1442333333,609.6 -1.2499103611,60.15884788890001,609.6 -1.2558708651,60.15926527530001,609.6 -1.2617318323,60.1599485109,609.6 -1.2674456667,60.1608920556,609.6 -1.2743027778,60.1462833333,609.6 -1.2567777778,60.1442333333,609.6 + + + + +
+ + EGRU019C LERWICK/TINGWALL RWY 20 + 601424N 0011349W -
601417N 0011245W -
601323N 0011311W thence anti-clockwise by the arc of a circle radius 2 NM centred on 601131N 0011437W to
601330N 0011414W -
601424N 0011349W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2301611111,60.2400916667,609.6 -1.2372617778,60.22503875,609.6 -1.2312903432,60.22461891820001,609.6 -1.2254195327,60.2239327561,609.6 -1.2196972778,60.2229858889,609.6 -1.2125861111,60.23804444440001,609.6 -1.2301611111,60.2400916667,609.6 + + + + +
+ + EGRU020 HMP CHANNINGS WOOD + 503110N 0033918W -
503108N 0033842W -
503054N 0033836W -
503029N 0033847W -
503022N 0033920W -
503034N 0033946W -
503049N 0033947W -
503110N 0033918W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 291 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.655,50.5194,213.36 -3.6629972222,50.513475,213.36 -3.6626555556,50.50954444440001,213.36 -3.655516666700001,50.5061305556,213.36 -3.6463638889,50.5079861111,213.36 -3.6433027778,50.5149527778,213.36 -3.645099999999999,50.51877222220001,213.36 -3.655,50.5194,213.36 + + + + +
+ + EGRU021 HMP DARTMOOR + 503318N 0035946W -
503312N 0035925W -
503259N 0035917W -
503247N 0035924W -
503235N 0035957W -
503308N 0040020W -
503318N 0035946W
Upper limit: 1900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 1403 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.996130555600001,50.5549111111,579.12 -4.0056361111,50.5521527778,579.12 -3.9991277778,50.5430111111,579.12 -3.9899416667,50.54638333330001,579.12 -3.9880027778,50.54969722220001,579.12 -3.9904138889,50.5534277778,579.12 -3.996130555600001,50.5549111111,579.12 + + + + +
+ + EGRU022 HMP EXETER + 504400N 0033157W -
504357N 0033136W -
504332N 0033124W -
504325N 0033218W -
504352N 0033230W -
504400N 0033157W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 184 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5325777778,50.7332972222,182.88 -3.5415472222,50.731125,182.88 -3.5382944444,50.72348888889999,182.88 -3.5232972222,50.7256,182.88 -3.526575,50.7326305556,182.88 -3.5325777778,50.7332972222,182.88 + + + + +
+ + EGRU023 HMP GUYS MARSH + 505925N 0021325W -
505928N 0021252W -
505901N 0021229W -
505842N 0021316W -
505909N 0021348W -
505925N 0021325W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 346 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2236361111,50.9901722222,243.84 -2.2300527778,50.98580833329999,243.84 -2.2209777778,50.97821111110001,243.84 -2.2080888889,50.9837472222,243.84 -2.2145111111,50.9911916667,243.84 -2.2236361111,50.9901722222,243.84 + + + + +
+ + EGRU024 HMP ISLE OF WIGHT + 504308N 0011912W -
504318N 0011810W -
504227N 0011750W -
504216N 0011840W -
504308N 0011912W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 157 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3200083333,50.7187833333,182.88 -1.3110416667,50.7045388889,182.88 -1.2973027778,50.7075833333,182.88 -1.3026555556,50.7215638889,182.88 -1.3200083333,50.7187833333,182.88 + + + + +
+ + EGRU025 HMP LEWES + 505243N 0000018W -
505231N 0000006E -
505216N 0000007E -
505200N 0000032W -
505228N 0000058W -
505243N 0000018W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 207 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0049527778,50.8787138889,213.36 -0.01605,50.874425,213.36 -0.0089611111,50.86659999999999,213.36 0.00205,50.8709777778,213.36 0.0016305556,50.8752805556,213.36 -0.0049527778,50.8787138889,213.36 + + + + +
+ + EGRU026 HMP PORTLAND + 503323N 0022549W -
503325N 0022513W -
503306N 0022455W -
503247N 0022444W -
503243N 0022529W -
503306N 0022556W -
503323N 0022549W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 382 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.430325,50.5564944444,243.84 -2.43215,50.5517,243.84 -2.4248138889,50.54528055559999,243.84 -2.4123027778,50.5464833333,243.84 -2.4152,50.5516916667,243.84 -2.4202333333,50.55705,243.84 -2.430325,50.5564944444,243.84 + + + + +
+ + EGRU027 HMP THE VERNE + 503359N 0022615W -
503358N 0022546W -
503333N 0022528W -
503320N 0022612W -
503326N 0022617W -
503327N 0022640W -
503351N 0022636W -
503359N 0022615W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 476 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4375472222,50.56629444440001,274.32 -2.4433861111,50.5640555556,274.32 -2.4445305556,50.55748055559999,274.32 -2.4380888889,50.5572861111,274.32 -2.4366027778,50.5555277778,274.32 -2.4245555556,50.5591222222,274.32 -2.4293055556,50.5659888889,274.32 -2.4375472222,50.56629444440001,274.32 + + + + +
+ + EGRU101A HAVERFORDWEST + A circle, 2 NM radius, centred at 515000N 0045739W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9608472222,51.86660115400001,609.6 -4.9663762085,51.8664245833,609.6 -4.9718464575,51.8658967469,609.6 -4.97719986,51.8650232521,609.6 -4.9823795559,51.8638133777,609.6 -4.9873305421,51.8622799751,609.6 -4.9920002595,51.8604393304,609.6 -4.9963391531,51.85831099090001,609.6 -5.0003012001,51.85591755630001,609.6 -5.0038443986,51.8532844373,609.6 -5.0069312133,51.85043958459999,609.6 -5.0095289721,51.8474131912,609.6 -5.0116102105,51.8442373706,609.6 -5.0131529595,51.84094581480001,609.6 -5.0141409747,51.8375734365,609.6 -5.0145639039,51.83415599749999,609.6 -5.0144173916,51.83072972970001,609.6 -5.0137031196,51.82733095030001,609.6 -5.0124287842,51.82399567689999,609.6 -5.010608009,51.8207592466,609.6 -5.0082601956,51.8176559415,609.6 -5.0054103137,51.8147186271,609.6 -5.0020886333,51.8119784046,609.6 -4.9983304008,51.8094642829,609.6 -4.9941754641,51.8072028728,609.6 -4.9896678499,51.80521810659999,609.6 -4.9848552974,51.8035309858,609.6 -4.9797887545,51.80215936050001,609.6 -4.9745218403,51.8011177411,609.6 -4.9691102802,51.8004171461,609.6 -4.9636113201,51.80006498619999,609.6 -4.9580831243,51.80006498619999,609.6 -4.9525841643,51.8004171461,609.6 -4.9471726042,51.8011177411,609.6 -4.9419056899,51.80215936050001,609.6 -4.9368391471,51.8035309858,609.6 -4.9320265946,51.80521810659999,609.6 -4.9275189803,51.8072028728,609.6 -4.9233640436,51.8094642829,609.6 -4.9196058111,51.8119784046,609.6 -4.9162841307,51.8147186271,609.6 -4.9134342489,51.8176559415,609.6 -4.9110864354,51.8207592466,609.6 -4.9092656602,51.82399567689999,609.6 -4.9079913248,51.82733095030001,609.6 -4.9072770529,51.83072972970001,609.6 -4.9071305405,51.83415599749999,609.6 -4.9075534697,51.8375734365,609.6 -4.908541485,51.84094581480001,609.6 -4.9100842339,51.8442373706,609.6 -4.9121654723,51.8474131912,609.6 -4.9147632311,51.85043958459999,609.6 -4.9178500458,51.8532844373,609.6 -4.9213932444,51.85591755630001,609.6 -4.9253552913,51.85831099090001,609.6 -4.929694185,51.8604393304,609.6 -4.9343639023,51.8622799751,609.6 -4.9393148885,51.8638133777,609.6 -4.9444945845,51.8650232521,609.6 -4.9498479869,51.8658967469,609.6 -4.9553182359,51.8664245833,609.6 -4.9608472222,51.86660115400001,609.6 + + + + +
+ + EGRU101B HAVERFORDWEST RWY 03 + 514716N 0045940W -
514732N 0050025W -
514825N 0045937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
514809N 0045851W -
514716N 0045940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9943083333,51.7878444444,609.6 -4.9809063333,51.8024292222,609.6 -4.9853153742,51.8036751517,609.6 -4.9895255747,51.80516225289999,609.6 -4.9935026944,51.80687844439999,609.6 -5.0068972222,51.79229722220001,609.6 -4.9943083333,51.7878444444,609.6 + + + + +
+ + EGRU101C HAVERFORDWEST RWY 21 + 515243N 0045539W -
515227N 0045454W -
515135N 0045541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
515151N 0045627W -
515243N 0045539W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.9275583333,51.8785055556,609.6 -4.9407586667,51.86418891669999,609.6 -4.9363448359,51.86294117239999,609.6 -4.9321309303,51.8614520004,609.6 -4.9281513056,51.8597335556,609.6 -4.9149444444,51.8740527778,609.6 -4.9275583333,51.8785055556,609.6 + + + + +
+ + EGRU101D HAVERFORDWEST RWY 09 + 514940N 0050222W -
515012N 0050224W -
515015N 0050051W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
514942N 0050050W -
514940N 0050222W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.0394888889,51.82773611110001,609.6 -5.0139970278,51.8284296389,609.6 -5.0144928085,51.8314198647,609.6 -5.0145512565,51.8344256075,609.6 -5.0141718056,51.8374223611,609.6 -5.0401138889,51.83671666669999,609.6 -5.0394888889,51.82773611110001,609.6 + + + + +
+ + EGRU101E HAVERFORDWEST RWY 27 + 515027N 0045311W -
514955N 0045309W -
514953N 0045426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515000N 0045739W to
515025N 0045430W -
515027N 0045311W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.886525,51.8408111111,609.6 -4.9082875833,51.8402431944,609.6 -4.9074941979,51.8372777002,609.6 -4.9071359293,51.8342799592,609.6 -4.9072156111,51.8312744167,609.6 -4.8859027778,51.8318305556,609.6 -4.886525,51.8408111111,609.6 + + + + +
+ + EGRU103A SWANSEA + A circle, 2 NM radius, centred at 513619N 0040404W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0677777778,51.6385691199,609.6 -4.0732789905,51.6383925433,609.6 -4.0787217619,51.6378646894,609.6 -4.0840482758,51.6369911656,609.6 -4.0892019586,51.63578125080001,609.6 -4.0941280843,51.63424779660001,609.6 -4.0987743581,51.6324070894,609.6 -4.1030914745,51.6302786768,609.6 -4.1070336417,51.6278851591,609.6 -4.1105590688,51.6252519474,609.6 -4.1136304084,51.6224069933,609.6 -4.1162151518,51.6193804903,609.6 -4.1182859716,51.61620455290001,609.6 -4.1198210079,51.61291287409999,609.6 -4.1208040969,51.6095403677,609.6 -4.1212249367,51.606122797,609.6 -4.1210791924,51.6026963949,609.6 -4.120368536,51.5992974802,609.6 -4.1191006239,51.595962072,609.6 -4.1172890099,51.592725509,609.6 -4.1149529973,51.5896220749,609.6 -4.1121174298,51.58668463670001,609.6 -4.1088124245,51.58394429730001,609.6 -4.1050730509,51.5814300673,609.6 -4.1009389566,51.57916855869999,609.6 -4.0964539477,51.5771837053,609.6 -4.0916655245,51.57549650990001,609.6 -4.0866243798,51.5741248235,609.6 -4.0813838645,51.5730831575,609.6 -4.0759994259,51.572382531,609.6 -4.0705280237,51.5720303553,609.6 -4.0650275318,51.5720303553,609.6 -4.0595561297,51.572382531,609.6 -4.054171691,51.5730831575,609.6 -4.0489311758,51.5741248235,609.6 -4.0438900311,51.57549650990001,609.6 -4.0391016078,51.5771837053,609.6 -4.0346165989,51.57916855869999,609.6 -4.0304825047,51.5814300673,609.6 -4.026743131,51.58394429730001,609.6 -4.0234381258,51.58668463670001,609.6 -4.0206025582,51.5896220749,609.6 -4.0182665456,51.592725509,609.6 -4.0164549317,51.595962072,609.6 -4.0151870195,51.5992974802,609.6 -4.0144763632,51.6026963949,609.6 -4.0143306189,51.606122797,609.6 -4.0147514587,51.6095403677,609.6 -4.0157345476,51.61291287409999,609.6 -4.017269584,51.61620455290001,609.6 -4.0193404037,51.6193804903,609.6 -4.0219251472,51.6224069933,609.6 -4.0249964868,51.6252519474,609.6 -4.0285219138,51.6278851591,609.6 -4.0324640811,51.6302786768,609.6 -4.0367811974,51.6324070894,609.6 -4.0414274713,51.63424779660001,609.6 -4.0463535969,51.63578125080001,609.6 -4.0515072798,51.6369911656,609.6 -4.0568337937,51.6378646894,609.6 -4.0622765651,51.6383925433,609.6 -4.0677777778,51.6385691199,609.6 + + + + +
+ + EGRU103B SWANSEA RWY 04 + 513341N 0040638W -
513400N 0040720W -
513453N 0040618W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513434N 0040536W -
513341N 0040638W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1105694444,51.5614305556,609.6 -4.0933516667,51.5760447778,609.6 -4.0974772875,51.5775992074,609.6 -4.1013615228,51.5793789018,609.6 -4.1049727778,51.58136938889999,609.6 -4.1221888889,51.5667527778,609.6 -4.1105694444,51.5614305556,609.6 + + + + +
+ + EGRU103C SWANSEA RWY 22 + 513854N 0040133W -
513835N 0040052W -
513745N 0040150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513804N 0040232W -
513854N 0040133W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0259555556,51.6483027778,609.6 -4.0422406389,51.6345286389,609.6 -4.0381074205,51.632975828,609.6 -4.0342163026,51.631197314,609.6 -4.030599,51.62920761110001,609.6 -4.0143111111,51.6429805556,609.6 -4.0259555556,51.6483027778,609.6 + + + + +
+ + EGRU103D SWANSEA RWY 10 + 513606N 0040854W -
513638N 0040848W -
513632N 0040715W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513559N 0040714W -
513606N 0040854W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1483194444,51.6016305556,609.6 -4.1204896111,51.5997253611,609.6 -4.1210842429,51.602737017,609.6 -4.1212361072,51.605769878,609.6 -4.1209438611,51.60879875,609.6 -4.1467305556,51.6105638889,609.6 -4.1483194444,51.6016305556,609.6 + + + + +
+ + EGRU103E SWANSEA RWY 28 + 513600N 0035931W -
513527N 0035937W -
513534N 0040106W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513619N 0040404W to
513605N 0040053W -
513600N 0035931W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9918916667,51.5998777778,609.6 -4.0146683056,51.6014628333,609.6 -4.015448363,51.5984676719,609.6 -4.0166629251,51.5955291688,609.6 -4.0183018333,51.5926717222,609.6 -3.9934777778,51.5909444444,609.6 -3.9918916667,51.5998777778,609.6 + + + + +
+ + EGRU104A ST ATHAN + 512532N 0032328W -
512241N 0032410W thence clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to -
512532N 0032328W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3911111111,51.4255555556,609.6 -3.394727747500001,51.4281636406,609.6 -3.3987267963,51.4305415517,609.6 -3.4030987649,51.4326475738,609.6 -3.4077965855,51.4344590111,609.6 -3.4127696603,51.4359563401,609.6 -3.4179644073,51.4371234209,609.6 -3.4233248408,51.4379476723,609.6 -3.428793177899999,51.43842020819999,609.6 -3.4343104649,51.4385359342,609.6 -3.4398172168,51.43829360260001,609.6 -3.445254063,51.437695826,609.6 -3.4505623917,51.4367490491,609.6 -3.4556849849,51.4354634786,609.6 -3.4605666395,51.4338529727,609.6 -3.465154765,51.4319348906,609.6 -3.4693999519,51.42972990429999,609.6 -3.4732565058,51.42726177509999,609.6 -3.476682940299999,51.4245570954,609.6 -3.4796424223,51.4216450019,609.6 -3.4821031677,51.4185568596,609.6 -3.4840387809,51.4153259234,609.6 -3.4854285349,51.4119869789,609.6 -3.4862575909,51.40857596650001,609.6 -3.4865171524,51.40512959469999,609.6 -3.4862045549,51.40168494419999,609.6 -3.4853232893,51.39827906879999,609.6 -3.4838829581,51.3949485973,609.6 -3.4818991679,51.3917293395,609.6 -3.4793933557,51.3886559024,609.6 -3.4763925551,51.38576131840001,609.6 -3.4729291017,51.3830766918,609.6 -3.4690402832,51.3806308656,609.6 -3.4647679371,51.3784501128,609.6 -3.4601580005,51.37655785539999,609.6 -3.4552600171,51.3749744143,609.6 -3.4501266063,51.3737167921,609.6 -3.4448129005,51.3727984916,609.6 -3.4393759557,51.3722293717,609.6 -3.4338741428,51.3720155421,609.6 -3.4283665243,51.3721592983,609.6 -3.4229122247,51.37265909719999,609.6 -3.4175698,51.3735095732,609.6 -3.412396612699999,51.37470159559999,609.6 -3.4074482194,51.3762223661,609.6 -3.4027777778,51.3780555556,609.6 -3.3911111111,51.4255555556,609.6 + + + + +
+ + EGRU104B ST ATHAN RWY 07 + 512308N 0033043W -
512339N 0033058W -
512400N 0032909W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512419N 0032600W to
512329N 0032854W -
512308N 0033043W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.511936111099999,51.38549999999999,609.6 -3.4816345,51.39129580560001,609.6 -3.483453917,51.3940757942,609.6 -3.4848655896,51.39694704319999,609.6 -3.4858579444,51.3998861944,609.6 -3.5161222222,51.3940972222,609.6 -3.511936111099999,51.38549999999999,609.6 + + + + +
+ + EGRU104C ST ATHAN RWY 25 + 512530N 0032116W -
512459N 0032101W -
512428N 0032344W -
512503N 0032335W -
512530N 0032116W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3543944444,51.424925,609.6 -3.3930726111,51.4175764444,609.6 -3.3954943889,51.4077211111,609.6 -3.3502,51.4163277778,609.6 -3.3543944444,51.424925,609.6 + + + + +
+ + EGRU105A CARDIFF + 512532N 0032328W thence clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to
512241N 0032410W -
512532N 0032328W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3911111111,51.4255555556,609.6 -3.4027777778,51.3780555556,609.6 -3.3998652394,51.3747004374,609.6 -3.3964158735,51.3715489884,609.6 -3.392519759699999,51.3686086909,609.6 -3.3882097622,51.36590428489999,609.6 -3.3835222082,51.36345852119999,609.6 -3.3784965819,51.36129197170001,609.6 -3.3731751922,51.3594228567,609.6 -3.367602817999999,51.3578668934,609.6 -3.361826333399999,51.35663716399999,609.6 -3.3558943152,51.35574400710001,609.6 -3.349856637899999,51.355194931,609.6 -3.3437640568,51.3549945514,609.6 -3.337667784999999,51.35514455260001,609.6 -3.3316190667,51.35564367369999,609.6 -3.3256687493,51.3564877191,609.6 -3.3198668596,51.3576695933,609.6 -3.3142621866,51.3591793603,609.6 -3.3089018737,51.36100432629999,609.6 -3.303831025,51.3631291457,609.6 -3.2990923271,51.36553594940001,609.6 -3.2947256915,51.36820449380001,609.6 -3.2907679193,51.37111233020001,609.6 -3.2872523906,51.3742349926,609.6 -3.284208783,51.377546202,609.6 -3.2816628197,51.3810180874,609.6 -3.2796360502,51.3846214184,609.6 -3.2781456658,51.3883258514,609.6 -3.277204351,51.39210018400001,609.6 -3.2768201726,51.3959126172,609.6 -3.2769965071,51.3997310233,609.6 -3.2777320074,51.4035232161,609.6 -3.279020609999999,51.40725722260001,609.6 -3.2808515811,51.4109015527,609.6 -3.283209603,51.4144254654,609.6 -3.2860748989,51.4177992282,609.6 -3.289423397200001,51.42099436940001,609.6 -3.2932269306,51.4239839189,609.6 -3.2974534725,51.4267426368,609.6 -3.3020674054,51.42924722790001,609.6 -3.3070298211,51.4314765391,609.6 -3.3122988491,51.43341173959999,609.6 -3.3178300112,51.4350364804,609.6 -3.3235765985,51.4363370339,609.6 -3.329490068200001,51.43730241069999,609.6 -3.3355204563,51.4379244528,609.6 -3.341616803,51.4381979032,609.6 -3.3477275864,51.4381204511,609.6 -3.353801161799999,51.437692751,609.6 -3.3597862013,51.4369184174,609.6 -3.3656321314,51.435803994,609.6 -3.3712895632,51.4343588982,609.6 -3.3767107132,51.4325953402,609.6 -3.3818498086,51.4305282199,609.6 -3.3866634765,51.4281749996,609.6 -3.3911111111,51.4255555556,609.6 + + + + +
+ + EGRU105B CARDIFF RWY 12 + 512500N 0032523W -
512529N 0032500W -
512502N 0032335W -
512429N 0032344W -
512500N 0032523W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4230194444,51.4166861111,609.6 -3.395426,51.40799941670001,609.6 -3.3931304444,51.4173411111,609.6 -3.416541666700001,51.4247111111,609.6 -3.4230194444,51.4166861111,609.6 + + + + +
+ + EGRU105C CARDIFF RWY 30 + 512234N 0031546W -
512205N 0031610W -
512226N 0031715W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512348N 0032036W to
512255N 0031652W -
512234N 0031546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2628444444,51.3761972222,609.6 -3.2810616111,51.3819633056,609.6 -3.2829113154,51.3791942869,609.6 -3.2850748667,51.3765158529,609.6 -3.2875409722,51.3739419167,609.6 -3.2693111111,51.3681722222,609.6 -3.2628444444,51.3761972222,609.6 + + + + +
+ + EGRU106A BRISTOL + A circle, 2.5 NM radius, centred at 512258N 0024309W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7191,51.4242851807,609.6 -2.725241868,51.4241074951,609.6 -2.731331194,51.42357595829999,609.6 -2.7373158889,51.4226951174,609.6 -2.7431447661,51.421472507,609.6 -2.7487679819,51.4199185848,609.6 -2.7541374654,51.4180466408,609.6 -2.7592073311,51.41587268349999,609.6 -2.7639342736,51.41341530139999,609.6 -2.7682779384,51.4106955036,609.6 -2.772201267,51.4077365385,609.6 -2.7756708136,51.4045636943,609.6 -2.7786570288,51.4012040819,609.6 -2.7811345104,51.3976864016,609.6 -2.7830822176,51.3940406978,609.6 -2.7844836469,51.3902981006,609.6 -2.7853269691,51.3864905603,609.6 -2.7856051262,51.3826505733,609.6 -2.7853158864,51.3788109052,609.6 -2.7844618587,51.3750043104,609.6 -2.7830504661,51.3712632532,609.6 -2.7810938767,51.3676196314,609.6 -2.7786088966,51.3641045045,609.6 -2.7756168221,51.36074782950001,609.6 -2.7721432548,51.357578207,609.6 -2.7682178809,51.3546226381,609.6 -2.7638742162,51.35190629520001,609.6 -2.7591493189,51.3494523093,609.6 -2.7540834738,51.3472815737,609.6 -2.7487198497,51.3454125672,609.6 -2.7431041323,51.3438611982,609.6 -2.7372841373,51.3426406699,609.6 -2.7313094058,51.341761369,609.6 -2.7252307852,51.34123077780001,609.6 -2.7191,51.341053411,609.6 -2.7129692148,51.34123077780001,609.6 -2.7068905942,51.341761369,609.6 -2.7009158627,51.3426406699,609.6 -2.6950958677,51.3438611982,609.6 -2.6894801503,51.3454125672,609.6 -2.6841165262,51.3472815737,609.6 -2.6790506811,51.3494523093,609.6 -2.6743257838,51.35190629520001,609.6 -2.6699821191,51.3546226381,609.6 -2.6660567452,51.357578207,609.6 -2.6625831779,51.36074782950001,609.6 -2.6595911034,51.3641045045,609.6 -2.6571061233,51.3676196314,609.6 -2.6551495339,51.3712632532,609.6 -2.6537381413,51.3750043104,609.6 -2.6528841136,51.3788109052,609.6 -2.6525948738,51.3826505733,609.6 -2.6528730309,51.3864905603,609.6 -2.6537163531,51.3902981006,609.6 -2.6551177824,51.3940406978,609.6 -2.6570654896,51.3976864016,609.6 -2.6595429712,51.4012040819,609.6 -2.6625291864,51.4045636943,609.6 -2.665998733,51.4077365385,609.6 -2.6699220616,51.4106955036,609.6 -2.6742657264,51.41341530139999,609.6 -2.6789926689,51.41587268349999,609.6 -2.6840625346,51.4180466408,609.6 -2.6894320181,51.4199185848,609.6 -2.6950552339,51.421472507,609.6 -2.7008841111,51.4226951174,609.6 -2.706868806,51.42357595829999,609.6 -2.712958132,51.4241074951,609.6 -2.7191,51.4242851807,609.6 + + + + +
+ + EGRU106B BRISTOL RWY 09 + 512229N 0024817W -
512302N 0024820W -
512304N 0024708W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to
512232N 0024705W -
512229N 0024817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8047333333,51.3748027778,609.6 -2.784633,51.3755981944,609.6 -2.7852789747,51.3785715963,609.6 -2.785580968,51.3815663965,609.6 -2.7855373333,51.3845670278,609.6 -2.8056222222,51.38377222220001,609.6 -2.8047333333,51.3748027778,609.6 + + + + +
+ + EGRU106C BRISTOL RWY 27 + 512325N 0023807W -
512253N 0023804W -
512251N 0023910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512258N 0024309W to
512323N 0023913W -
512325N 0023807W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6352888889,51.3904027778,609.6 -2.6535468333,51.389704,609.6 -2.6529092331,51.38672981640001,609.6 -2.6526158735,51.3837346154,609.6 -2.6526682222,51.3807339722,609.6 -2.6343944444,51.3814333333,609.6 -2.6352888889,51.3904027778,609.6 + + + + +
+ + EGRU107A YEOVILTON + 505817N 0024035W thence clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505804N 0023747W -
505817N 0024035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6762913333,50.97146936109999,609.6 -2.6298215278,50.96784299999999,609.6 -2.6239672815,50.96893044029999,609.6 -2.618297061,50.9703547957,609.6 -2.6128593738,50.9721039029,609.6 -2.6077007473,50.974162805,609.6 -2.6028653391,50.97651389319999,609.6 -2.5983945605,50.9791370573,609.6 -2.594326723,50.98200985630001,609.6 -2.5906967097,50.9851077091,609.6 -2.5875356765,50.9884041042,609.6 -2.5848707832,50.991870825,609.6 -2.5827249586,50.9954781906,609.6 -2.581116701,50.99919530889999,609.6 -2.5800599161,51.00299034069999,609.6 -2.5795637937,51.0068307715,609.6 -2.5796327246,51.0106836897,609.6 -2.5802662577,51.01451606890001,609.6 -2.5814590998,51.0182950504,609.6 -2.5832011558,51.0219882257,609.6 -2.5854776109,51.0255639143,609.6 -2.5882690536,51.0289914368,609.6 -2.5915516385,51.0322413781,609.6 -2.5952972881,51.0352858415,609.6 -2.5994739312,51.0380986885,609.6 -2.6040457767,51.0406557648,609.6 -2.60897362,51.0429351086,609.6 -2.6142151797,51.0449171406,609.6 -2.6197254613,51.0465848329,609.6 -2.6254571452,51.0479238563,609.6 -2.6313609955,51.0489227048,609.6 -2.6373862853,51.0495727947,609.6 -2.643481236,51.049868539,609.6 -2.6495934654,51.0498073961,609.6 -2.6556704418,51.0493898914,609.6 -2.6616599388,51.0486196131,609.6 -2.6675104878,51.04750318080001,609.6 -2.6731718236,51.0460501886,609.6 -2.6785953191,51.04427312149999,609.6 -2.6837344058,51.0421872477,609.6 -2.6885449756,51.0398104864,609.6 -2.6929857609,51.0371632529,609.6 -2.6970186893,51.03426828180001,609.6 -2.7006092105,51.0311504313,609.6 -2.7037265914,51.0278364679,609.6 -2.7063441786,51.0243548361,609.6 -2.708439624,51.0207354127,609.6 -2.7099950736,51.01700925039999,609.6 -2.7109973165,51.01320830969999,609.6 -2.7114378947,51.0093651849,609.6 -2.7113131703,51.0055128239,609.6 -2.7106243521,51.00168424579999,609.6 -2.7093774809,50.9979122577,609.6 -2.7075833724,50.994229174,609.6 -2.7052575206,50.9906665399,609.6 -2.7024199611,50.9872548621,609.6 -2.6990950954,50.9840233479,609.6 -2.6953114796,50.9809996566,609.6 -2.6911015776,50.97820966340001,609.6 -2.6865014817,50.97567723939999,609.6 -2.6815506027,50.9734240479,609.6 -2.6762913333,50.97146936109999,609.6 + + + + +
+ + EGRU107B YEOVILTON RWY 04 + 505754N 0024053W -
505814N 0024134W -
505832N 0024111W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505817N 0024035W -
505817N 0024026W -
505754N 0024053W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6813681667,50.9650763611,609.6 -2.6739531389,50.9712873611,609.6 -2.6762913333,50.97146936109999,609.6 -2.6815638587,50.9734295096,609.6 -2.6865262778,50.97568966670001,609.6 -2.6927310556,50.9704911944,609.6 -2.6813681667,50.9650763611,609.6 + + + + +
+ + EGRU107C YEOVILTON RWY 22 + 510310N 0023540W -
510250N 0023459W -
510210N 0023547W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
510232N 0023626W -
510310N 0023540W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5943472222,51.0527433889,609.6 -2.6070863889,51.04211411110001,609.6 -2.6033052479,51.0402731247,609.6 -2.5997455139,51.03826444290001,609.6 -2.5964258333,51.0360986111,609.6 -2.5829642222,51.0473286111,609.6 -2.5943472222,51.0527433889,609.6 + + + + +
+ + EGRU107D YEOVILTON RWY 08 + 505950N 0024354W -
510022N 0024400W -
510028N 0024241W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
505956N 0024235W -
505950N 0024354W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7315610556,50.9971264722,609.6 -2.7097279722,50.9988129167,609.6 -2.7106431331,51.0017583572,609.6 -2.7112195574,51.0047377531,609.6 -2.7114541944,51.0077356111,609.6 -2.7332775556,51.0060498889,609.6 -2.7315610556,50.9971264722,609.6 + + + + +
+ + EGRU107E YEOVILTON RWY 26 + 510110N 0023334W -
510038N 0023328W -
510032N 0023446W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510030N 0023844W to
510104N 0023452W -
510110N 0023334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5594051667,51.019364,609.6 -2.5812353056,51.017707,609.6 -2.5803261568,51.0147607937,609.6 -2.5797560879,51.01178091279999,609.6 -2.579528,51.00878286109999,609.6 -2.5576881667,51.0104406111,609.6 -2.5594051667,51.019364,609.6 + + + + +
+ + EGRU108 PORT OF DOVER + 510907N 0012206E thence clockwise by the arc of a circle radius 2.25 NM centred on 510800N 0011900E to
510656N 0011551E -
510907N 0012206E
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: Flight permitted by any unmanned aircraft:
operating in the service of the Port of Dover Police;
operating in the service of the Kent Police;
operating in the service of Kent Fire and Rescue Service; or
operating with the permission of the Port of Dover Police.

SI 1329/2019.

Contact: Refer to Statutory Instrument.

]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3683333333,51.1519444444,304.8 1.2641666667,51.1155555556,304.8 1.2672038795,51.1125068064,304.8 1.270605115,51.10961907119999,304.8 1.2744300642,51.1069497853,304.8 1.2786434752,51.1045235011,304.8 1.2832065412,51.1023625326,304.8 1.2880772581,51.1004867505,304.8 1.2932108101,51.098913401,304.8 1.2985599804,51.09765694829999,304.8 1.304075583,51.096728942,304.8 1.309706913,51.09613791200001,304.8 1.3154022092,51.0958892907,304.8 1.3211091266,51.095985363,304.8 1.3267752144,51.096425246,304.8 1.3323483941,51.0972048968,304.8 1.3377774353,51.09831714909999,304.8 1.3430124231,51.0997517792,304.8 1.3480052141,51.1014955989,304.8 1.3527098772,51.1035325759,304.8 1.357083114,51.1058439808,304.8 1.3610846561,51.1084085577,304.8 1.3646776353,51.1112027189,304.8 1.3678289231,51.1142007606,304.8 1.3705094373,51.1173750984,304.8 1.3726944115,51.1206965203,304.8 1.3743636256,51.1241344542,304.8 1.375501596,51.12765724860001,304.8 1.3760977216,51.1312324636,304.8 1.3761463859,51.1348271693,304.8 1.3756470134,51.1384082484,304.8 1.3746040794,51.1419427016,304.8 1.3730270737,51.1453979519,304.8 1.3709304173,51.1487421452,304.8 1.3683333333,51.1519444444,304.8 + + + + +
+ + EGRU109A GLOUCESTERSHIRE + A circle, 2 NM radius, centred at 515339N 0021002W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1672222222,51.92745636330001,609.6 -2.172758683,51.9272797941,609.6 -2.1782363268,51.92675196230001,609.6 -2.1835969655,51.92587847519999,609.6 -2.1887836621,51.9246686117,609.6 -2.1937413388,51.9231352228,609.6 -2.1984173653,51.9212945947,609.6 -2.2027621196,51.91916627469999,609.6 -2.2067295166,51.91677286220001,609.6 -2.2102774978,51.9141397679,609.6 -2.2133684771,51.9112949423,609.6 -2.2159697386,51.9082685781,609.6 -2.2180537808,51.9050927885,609.6 -2.2195986054,51.9018012655,609.6 -2.2205879463,51.8984289213,609.6 -2.2210114378,51.8950115175,609.6 -2.2208647187,51.89158528549999,609.6 -2.2201494737,51.88818654209999,609.6 -2.2188734096,51.8848513047,609.6 -2.2170501689,51.88161490969999,609.6 -2.2146991796,51.8785116391,609.6 -2.2118454455,51.8755743577,609.6 -2.2085192775,51.8728341663,609.6 -2.2047559697,51.8703200735,609.6 -2.2005954239,51.8680586897,609.6 -2.1960817261,51.8660739467,609.6 -2.19126268,51.8643868459,609.6 -2.186189302,51.8630152369,609.6 -2.1809152833,51.8619736299,609.6 -2.1754964243,51.8612730433,609.6 -2.1699900479,51.8609208876,609.6 -2.1644543965,51.8609208876,609.6 -2.1589480201,51.8612730433,609.6 -2.1535291612,51.8619736299,609.6 -2.1482551424,51.8630152369,609.6 -2.1431817645,51.8643868459,609.6 -2.1383627184,51.8660739467,609.6 -2.1338490206,51.8680586897,609.6 -2.1296884748,51.8703200735,609.6 -2.125925167,51.8728341663,609.6 -2.122598999,51.8755743577,609.6 -2.1197452649,51.8785116391,609.6 -2.1173942755,51.88161490969999,609.6 -2.1155710348,51.8848513047,609.6 -2.1142949708,51.88818654209999,609.6 -2.1135797258,51.89158528549999,609.6 -2.1134330067,51.8950115175,609.6 -2.1138564981,51.8984289213,609.6 -2.1148458391,51.9018012655,609.6 -2.1163906636,51.9050927885,609.6 -2.1184747058,51.9082685781,609.6 -2.1210759673,51.9112949423,609.6 -2.1241669467,51.9141397679,609.6 -2.1277149279,51.91677286220001,609.6 -2.1316823249,51.91916627469999,609.6 -2.1360270792,51.9212945947,609.6 -2.1407031056,51.9231352228,609.6 -2.1456607824,51.9246686117,609.6 -2.1508474789,51.92587847519999,609.6 -2.1562081177,51.92675196230001,609.6 -2.1616857614,51.9272797941,609.6 -2.1672222222,51.92745636330001,609.6 + + + + +
+ + EGRU109B GLOUCESTERSHIRE RWY 04 + 515057N 0021212W -
515115N 0021255W -
515204N 0021200W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515148N 0021115W -
515057N 0021212W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2033861111,51.8490638889,609.6 -2.1874931944,51.8633313889,609.6 -2.191914972,51.8645919882,609.6 -2.1961347567,51.8660948525,609.6 -2.200118,51.8678276944,609.6 -2.2153277778,51.8541694444,609.6 -2.2033861111,51.8490638889,609.6 + + + + +
+ + EGRU109C GLOUCESTERSHIRE RWY 22 + 515605N 0020732W -
515547N 0020648W -
515501N 0020740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515521N 0020821W -
515605N 0020732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1254277778,51.93474999999999,609.6 -2.1390743333,51.92254116669999,609.6 -2.1350394219,51.92084952310001,609.6 -2.1312688435,51.9189390143,609.6 -2.1277935278,51.9168253333,609.6 -2.1134611111,51.9296444444,609.6 -2.1254277778,51.93474999999999,609.6 + + + + +
+ + EGRU109D GLOUCESTERSHIRE RWY 04G + 515105N 0021200W -
515123N 0021243W -
515203N 0021158W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515147N 0021112W -
515105N 0021200W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1998861111,51.8513694444,609.6 -2.1867024167,51.86313675,609.6 -2.1911634416,51.8643562518,609.6 -2.1954279461,51.86582079039999,609.6 -2.1994608889,51.8675183611,609.6 -2.2118055556,51.85649722219999,609.6 -2.1998861111,51.8513694444,609.6 + + + + +
+ + EGRU109E GLOUCESTERSHIRE RWY 22G + 515557N 0020735W -
515539N 0020652W -
515459N 0020737W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515520N 0020817W -
515557N 0020735W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1264444444,51.9325694444,609.6 -2.13813,51.92217436110001,609.6 -2.1341466733,51.92042848229999,609.6 -2.1304358591,51.9184665182,609.6 -2.1270280833,51.9163046389,609.6 -2.1145027778,51.9274444444,609.6 -2.1264444444,51.9325694444,609.6 + + + + +
+ + EGRU109F GLOUCESTERSHIRE RWY 09 + 515302N 0021455W -
515335N 0021500W -
515342N 0021316W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515310N 0021310W -
515302N 0021455W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.248525,51.8840111111,609.6 -2.2193798056,51.88600116669999,609.6 -2.2203588823,51.8889439051,609.6 -2.2209052777,51.8919292781,609.6 -2.2210144722,51.8949329722,609.6 -2.2501027778,51.8929472222,609.6 -2.248525,51.8840111111,609.6 + + + + +
+ + EGRU109G GLOUCESTERSHIRE RWY 27 + 515414N 0020522W -
515342N 0020517W -
515335N 0020648W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515339N 0021002W to
515408N 0020654W -
515414N 0020522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0895777778,51.9038138889,609.6 -2.1149658333,51.9021101667,609.6 -2.1140228124,51.8991634474,609.6 -2.1135131055,51.8961761338,609.6 -2.1134407778,51.8931725556,609.6 -2.0879944444,51.8948805556,609.6 -2.0895777778,51.9038138889,609.6 + + + + +
+ + EGRU110A KEMBLE + A circle, 2 NM radius, centred at 514005N 0020325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0570083333,51.7013520953,609.6 -2.0625171561,51.7011755203,609.6 -2.0679674566,51.7006476712,609.6 -2.0733013381,51.6997741554,609.6 -2.0784621486,51.6985642518,609.6 -2.0833950862,51.6970308118,609.6 -2.0880477837,51.6951901218,609.6 -2.0923708672,51.69306172940001,609.6 -2.0963184816,51.6906682346,609.6 -2.0998487782,51.68803504850001,609.6 -2.1029243581,51.6851901223,609.6 -2.1055126678,51.6821636495,609.6 -2.1075863423,51.67898774419999,609.6 -2.109123492,51.67569609939999,609.6 -2.1101079308,51.67232362830001,609.6 -2.1105293431,51.6689060938,609.6 -2.1103833884,51.6654797288,609.6 -2.1096717414,51.6620808513,609.6 -2.1084020693,51.65874548030001,609.6 -2.1065879451,51.65550895379999,609.6 -2.104248699,51.6524055552,609.6 -2.1014092092,51.6494681512,609.6 -2.0980996349,51.646727844,609.6 -2.0943550938,51.6442136437,609.6 -2.0902152886,51.64195216229999,609.6 -2.0857240857,51.6399673329,609.6 -2.0809290509,51.6382801581,609.6 -2.0758809469,51.6369084885,609.6 -2.0706331981,51.6358668353,609.6 -2.065241328,51.63516621749999,609.6 -2.0597623748,51.6348140461,609.6 -2.0542542919,51.6348140461,609.6 -2.0487753386,51.63516621749999,609.6 -2.0433834685,51.6358668353,609.6 -2.0381357198,51.6369084885,609.6 -2.0330876158,51.6382801581,609.6 -2.028292581,51.6399673329,609.6 -2.0238013781,51.64195216229999,609.6 -2.0196615729,51.6442136437,609.6 -2.0159170318,51.646727844,609.6 -2.0126074574,51.6494681512,609.6 -2.0097679677,51.6524055552,609.6 -2.0074287216,51.65550895379999,609.6 -2.0056145974,51.65874548030001,609.6 -2.0043449253,51.6620808513,609.6 -2.0036332783,51.6654797288,609.6 -2.0034873235,51.6689060938,609.6 -2.0039087359,51.67232362830001,609.6 -2.0048931747,51.67569609939999,609.6 -2.0064303243,51.67898774419999,609.6 -2.0085039989,51.6821636495,609.6 -2.0110923086,51.6851901223,609.6 -2.0141678885,51.68803504850001,609.6 -2.0176981851,51.6906682346,609.6 -2.0216457995,51.69306172940001,609.6 -2.0259688829,51.6951901218,609.6 -2.0306215804,51.6970308118,609.6 -2.035554518,51.6985642518,609.6 -2.0407153286,51.6997741554,609.6 -2.0460492101,51.7006476712,609.6 -2.0514995105,51.7011755203,609.6 -2.0570083333,51.7013520953,609.6 + + + + +
+ + EGRU110B KEMBLE RWY 08 + 513918N 0020819W -
513950N 0020828W -
514001N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
513929N 0020629W -
513918N 0020819W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1386894444,51.6548986944,609.6 -2.1081021667,51.65812861109999,609.6 -2.1093354747,51.6610331599,609.6 -2.1101428888,51.6639950203,609.6 -2.11051775,51.6669900833,609.6 -2.1410953889,51.6637611389,609.6 -2.1386894444,51.6548986944,609.6 + + + + +
+ + EGRU110C KEMBLE RWY 26 + 514052N 0015832W -
514020N 0015823W -
514009N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
514041N 0020021W -
514052N 0015832W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9754756111,51.68114966669999,609.6 -2.0058937778,51.67797455560001,609.6 -2.0046661483,51.675069011,609.6 -2.0038649379,51.672106485,609.6 -2.0034965833,51.66911111110001,609.6 -1.97306875,51.67228725,609.6 -1.9754756111,51.68114966669999,609.6 + + + + +
+ + EGRU110D KEMBLE RWY 08G + 513924N 0020746W -
513956N 0020755W -
514004N 0020638W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
513932N 0020630W -
513924N 0020746W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1295,51.6566277778,609.6 -2.1084556667,51.65886050000001,609.6 -2.1095817412,51.661782657,609.6 -2.1102796614,51.664756054,609.6 -2.1105436667,51.66775647219999,609.6 -2.1319166667,51.6654888889,609.6 -2.1295,51.6566277778,609.6 + + + + +
+ + EGRU110E KEMBLE RWY 26G + 514053N 0015853W -
514021N 0015844W -
514012N 0020013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514005N 0020325W to
514044N 0020023W -
514053N 0015853W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9814111111,51.6813694444,609.6 -2.0063030556,51.6787570556,609.6 -2.0049599261,51.67587043890001,609.6 -2.0040410911,51.6729202744,609.6 -2.0035539444,51.66993061109999,609.6 -1.9789916667,51.6725083333,609.6 -1.9814111111,51.6813694444,609.6 + + + + +
+ + EGRU111A FAIRFORD + A circle, 2.5 NM radius, centred at 514101N 0014724W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7900055556,51.7251302571,609.6 -1.7961881038,51.7249525789,609.6 -1.8023177604,51.7244210644,609.6 -1.80834209,51.72354026050001,609.6 -1.8142095653,51.7223177018,609.6 -1.8198700117,51.7207638457,609.6 -1.8252750386,51.7188919822,609.6 -1.8303784562,51.7167181193,609.6 -1.8351366718,51.7142608454,609.6 -1.8395090636,51.711541169,609.6 -1.8434583283,51.7085823379,609.6 -1.846950799,51.7054096398,609.6 -1.8499567317,51.7020501846,609.6 -1.8524505575,51.6985326718,609.6 -1.8544110975,51.6948871446,609.6 -1.8558217409,51.69114473199999,609.6 -1.8566705822,51.6873373829,609.6 -1.8569505185,51.6834975923,609.6 -1.8566593054,51.679658124,609.6 -1.8557995713,51.6758517307,609.6 -1.8543787901,51.67211087489999,609.6 -1.8524092124,51.66846745240001,609.6 -1.8499077569,51.6649525207,609.6 -1.8468958622,51.6615960349,609.6 -1.8433993005,51.65842659350001,609.6 -1.8394479548,51.6554711955,609.6 -1.8350755629,51.6527550116,609.6 -1.8303194283,51.6503011708,609.6 -1.8252201018,51.6481305646,609.6 -1.8198210368,51.6462616706,609.6 -1.8141682202,51.6447103955,609.6 -1.8083097825,51.64348994150001,609.6 -1.8022955908,51.6426106944,609.6 -1.796176827,51.6420801356,609.6 -1.7900055556,51.6419027797,609.6 -1.7838342841,51.6420801356,609.6 -1.7777155203,51.6426106944,609.6 -1.7717013286,51.64348994150001,609.6 -1.7658428909,51.6447103955,609.6 -1.7601900743,51.6462616706,609.6 -1.7547910093,51.6481305646,609.6 -1.7496916828,51.6503011708,609.6 -1.7449355482,51.6527550116,609.6 -1.7405631563,51.6554711955,609.6 -1.7366118107,51.65842659350001,609.6 -1.7331152489,51.6615960349,609.6 -1.7301033542,51.6649525207,609.6 -1.7276018987,51.66846745240001,609.6 -1.725632321,51.67211087489999,609.6 -1.7242115398,51.6758517307,609.6 -1.7233518057,51.679658124,609.6 -1.7230605927,51.6834975923,609.6 -1.7233405289,51.6873373829,609.6 -1.7241893702,51.69114473199999,609.6 -1.7256000136,51.6948871446,609.6 -1.7275605536,51.6985326718,609.6 -1.7300543794,51.7020501846,609.6 -1.7330603121,51.7054096398,609.6 -1.7365527828,51.7085823379,609.6 -1.7405020475,51.711541169,609.6 -1.7448744393,51.7142608454,609.6 -1.7496326549,51.7167181193,609.6 -1.7547360725,51.7188919822,609.6 -1.7601410994,51.7207638457,609.6 -1.7658015458,51.7223177018,609.6 -1.7716690211,51.72354026050001,609.6 -1.7776933507,51.7244210644,609.6 -1.7838230073,51.7249525789,609.6 -1.7900055556,51.7251302571,609.6 + + + + +
+ + EGRU111B FAIRFORD RWY 09 + 514037N 0015302W -
514110N 0015304W -
514112N 0015124W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to
514039N 0015123W -
514037N 0015302W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8839879444,51.6769958333,609.6 -1.8562672222,51.6776048333,609.6 -1.85678249,51.6805888471,609.6 -1.8569504954,51.68358818580001,609.6 -1.8567703056,51.68658725,609.6 -1.8844827222,51.6859784444,609.6 -1.8839879444,51.6769958333,609.6 + + + + +
+ + EGRU111C FAIRFORD RWY 27 + 514124N 0014146W -
514052N 0014144W -
514050N 0014324W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514101N 0014724W to
514122N 0014325W -
514124N 0014146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6959973611,51.6899902222,609.6 -1.7237330278,51.6894188889,609.6 -1.7232232057,51.686434517,609.6 -1.7230607719,51.68343506699999,609.6 -1.7232465278,51.6804361389,609.6 -1.6955025278,51.6810076389,609.6 -1.6959973611,51.6899902222,609.6 + + + + +
+ + EGRU112A NETHERAVON + A circle, 2 NM radius, centred at 511453N 0014517W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7548361111,51.28138782650001,609.6 -1.7602945509,51.2812112407,609.6 -1.7656950054,51.2806833593,609.6 -1.7709801093,51.27980978979999,609.6 -1.7760937305,51.2785998114,609.6 -1.7809815694,51.27706627589999,609.6 -1.7855917388,51.2752254703,609.6 -1.7898753167,51.2730969429,609.6 -1.7937868678,51.27070329439999,609.6 -1.7972849255,51.268069937,609.6 -1.8003324321,51.2652248232,609.6 -1.8028971307,51.262198148,609.6 -1.8049519048,51.259022027,609.6 -1.8064750628,51.255730155,609.6 -1.8074505644,51.2523574476,609.6 -1.807868186,51.2489396698,609.6 -1.807723624,51.2455130569,609.6 -1.8070185356,51.2421139298,609.6 -1.8057605153,51.2387783101,609.6 -1.80396301,51.2355415388,609.6 -1.8016451713,51.2324379023,609.6 -1.7988316485,51.2295002701,609.6 -1.7955523241,51.22675974749999,609.6 -1.7918419943,51.2242453475,609.6 -1.7877399989,51.22198368459999,609.6 -1.7832898041,51.2199986946,609.6 -1.7785385418,51.2183113821,609.6 -1.7735365123,51.2169396,609.6 -1.7683366538,51.2158978609,609.6 -1.7629939845,51.2151971852,609.6 -1.7575650239,51.2148449846,609.6 -1.7521071983,51.2148449846,609.6 -1.7466782377,51.2151971852,609.6 -1.7413355684,51.2158978609,609.6 -1.7361357099,51.2169396,609.6 -1.7311336805,51.2183113821,609.6 -1.7263824182,51.2199986946,609.6 -1.7219322233,51.22198368459999,609.6 -1.717830228,51.2242453475,609.6 -1.7141198982,51.22675974749999,609.6 -1.7108405737,51.2295002701,609.6 -1.7080270509,51.2324379023,609.6 -1.7057092122,51.2355415388,609.6 -1.7039117069,51.2387783101,609.6 -1.7026536866,51.2421139298,609.6 -1.7019485982,51.2455130569,609.6 -1.7018040362,51.2489396698,609.6 -1.7022216578,51.2523574476,609.6 -1.7031971595,51.255730155,609.6 -1.7047203175,51.259022027,609.6 -1.7067750915,51.262198148,609.6 -1.7093397901,51.2652248232,609.6 -1.7123872968,51.268069937,609.6 -1.7158853544,51.27070329439999,609.6 -1.7197969055,51.2730969429,609.6 -1.7240804834,51.2752254703,609.6 -1.7286906528,51.27706627589999,609.6 -1.7335784917,51.2785998114,609.6 -1.7386921129,51.27980978979999,609.6 -1.7439772169,51.2806833593,609.6 -1.7493776714,51.2812112407,609.6 -1.7548361111,51.28138782650001,609.6 + + + + +
+ + EGRU112B NETHERAVON RWY 04 + 511235N 0014751W -
511255N 0014830W -
511333N 0014739W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511312N 0014700W -
511235N 0014751W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7974191944,51.2095862778,609.6 -1.7833475,51.22002175,609.6 -1.7872618918,51.22174906989999,609.6 -1.7909127083,51.22369081829999,609.6 -1.7942702222,51.22583122220001,609.6 -1.8083353333,51.2153988056,609.6 -1.7974191944,51.2095862778,609.6 + + + + +
+ + EGRU112C NETHERAVON RWY 22 + 511718N 0014235W -
511657N 0014156W -
511613N 0014255W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511634N 0014335W -
511718N 0014235W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7097918611,51.2883559167,609.6 -1.7262928889,51.2761612222,609.6 -1.7223759775,51.2744320342,609.6 -1.7187238237,51.27248831,609.6 -1.7153661944,51.2703458889,609.6 -1.6988584444,51.2825434722,609.6 -1.7097918611,51.2883559167,609.6 + + + + +
+ + EGRU112D NETHERAVON RWY 11 + 511535N 0014957W -
511605N 0014941W -
511546N 0014809W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511515N 0014825W -
511535N 0014957W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8324731944,51.25960272219999,609.6 -1.8069665833,51.25427375,609.6 -1.8058682165,51.2571979427,609.6 -1.8043540669,51.26004808249999,609.6 -1.8024363889,51.2628009444,609.6 -1.8279352222,51.26812838890001,609.6 -1.8324731944,51.25960272219999,609.6 + + + + +
+ + EGRU112E NETHERAVON RWY 29 + 511412N 0014038W -
511341N 0014054W -
511400N 0014226W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511453N 0014517W to
511431N 0014210W -
511412N 0014038W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6772466667,51.2365466389,609.6 -1.7027167778,51.2419014167,609.6 -1.7038199435,51.2389779812,609.6 -1.7053382967,51.23612885570001,609.6 -1.7072593889,51.23337722220001,609.6 -1.6817815278,51.2280209167,609.6 -1.6772466667,51.2365466389,609.6 + + + + +
+ + EGRU113A BOSCOMBE + A circle, 2.5 NM radius, centred at 510912N 0014504W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7510111111,51.194925709,609.6 -1.7571224367,51.1947480177,609.6 -1.7631814827,51.1942164639,609.6 -1.7691364201,51.1933355946,609.6 -1.774936318,51.1921129447,609.6 -1.7805315813,51.1905589717,609.6 -1.7858743789,51.18868696609999,609.6 -1.790919054,51.1865129364,609.6 -1.7956225166,51.1840554715,609.6 -1.799944613,51.1813355807,609.6 -1.8038484688,51.178376513,609.6 -1.8073008037,51.1752035572,609.6 -1.8102722147,51.17184382440001,609.6 -1.812737425,51.1683260161,609.6 -1.814675497,51.16468017710001,609.6 -1.8160700079,51.16093743879999,609.6 -1.8169091861,51.1571297523,609.6 -1.8171860069,51.15328961539999,609.6 -1.8168982483,51.1494497946,609.6 -1.8160485048,51.14564304589999,609.6 -1.8146441607,51.141901835,609.6 -1.8126973227,51.13825806109999,609.6 -1.8102247121,51.1347427851,609.6 -1.8072475184,51.1313859657,609.6 -1.8037912153,51.1282162051,609.6 -1.7998853411,51.1252605058,609.6 -1.7955632448,51.1225440417,609.6 -1.7908618005,51.12008994509999,609.6 -1.7858210936,51.1179191107,609.6 -1.7804840787,51.1160500185,609.6 -1.7748962157,51.1144985778,609.6 -1.7691050838,51.1132779929,609.6 -1.7631599794,51.11239865100001,609.6 -1.7571114989,51.11186803500001,609.6 -1.7510111111,51.1116906599,609.6 -1.7449107234,51.11186803500001,609.6 -1.7388622428,51.11239865100001,609.6 -1.7329171384,51.1132779929,609.6 -1.7271260066,51.1144985778,609.6 -1.7215381435,51.1160500185,609.6 -1.7162011287,51.1179191107,609.6 -1.7111604217,51.12008994509999,609.6 -1.7064589775,51.1225440417,609.6 -1.7021368811,51.1252605058,609.6 -1.6982310069,51.1282162051,609.6 -1.6947747038,51.1313859657,609.6 -1.6917975101,51.1347427851,609.6 -1.6893248995,51.13825806109999,609.6 -1.6873780615,51.141901835,609.6 -1.6859737175,51.14564304589999,609.6 -1.6851239739,51.1494497946,609.6 -1.6848362153,51.15328961539999,609.6 -1.6851130361,51.1571297523,609.6 -1.6859522143,51.16093743879999,609.6 -1.6873467253,51.16468017710001,609.6 -1.6892847972,51.1683260161,609.6 -1.6917500075,51.17184382440001,609.6 -1.6947214185,51.1752035572,609.6 -1.6981737535,51.178376513,609.6 -1.7020776092,51.1813355807,609.6 -1.7063997056,51.1840554715,609.6 -1.7111031682,51.1865129364,609.6 -1.7161478433,51.18868696609999,609.6 -1.7214906409,51.1905589717,609.6 -1.7270859043,51.1921129447,609.6 -1.7328858021,51.1933355946,609.6 -1.7388407396,51.1942164639,609.6 -1.7448997855,51.1947480177,609.6 -1.7510111111,51.194925709,609.6 + + + + +
+ + EGRU113B BOSCOMBE RWY 05 + 510643N 0014908W -
510707N 0014941W -
510749N 0014822W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510724N 0014749W -
510643N 0014908W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8188315556,51.1118148056,609.6 -1.7969201389,51.12334375,609.6 -1.8002337125,51.12550256110001,609.6 -1.8032917451,51.127805952,609.6 -1.8060783056,51.1302419722,609.6 -1.8279827222,51.11871552780001,609.6 -1.8188315556,51.1118148056,609.6 + + + + +
+ + EGRU113C BOSCOMBE RWY 23 + 511139N 0014103W -
511114N 0014030W -
511035N 0014145W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511100N 0014218W -
511139N 0014103W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6841814444,51.19420625,609.6 -1.7050659722,51.1832688889,609.6 -1.7017510046,51.1811084272,609.6 -1.6986927047,51.1788033417,609.6 -1.6959069722,51.1763656389,609.6 -1.6750153333,51.1873056111,609.6 -1.6841814444,51.19420625,609.6 + + + + +
+ + EGRU113D BOSCOMBE RWY 05N + 510706N 0014834W -
510731N 0014907W -
510753N 0014826W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510727N 0014754W -
510706N 0014834W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8093775,51.118341,609.6 -1.7982730833,51.1241878611,609.6 -1.8014879624,51.1264067992,609.6 -1.8044405247,51.1287657571,609.6 -1.8071153889,51.1312524722,609.6 -1.8185353056,51.1252389167,609.6 -1.8093775,51.118341,609.6 + + + + +
+ + EGRU113E BOSCOMBE RWY 23N + 511114N 0014202W -
511049N 0014129W -
511039N 0014149W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511103N 0014223W -
511114N 0014202W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7004613056,51.1872856389,609.6 -1.7065058611,51.1841162222,609.6 -1.7030883915,51.18201788359999,609.6 -1.6999208758,51.179770037,609.6 -1.6970197778,51.1773844167,609.6 -1.6912912222,51.1803878056,609.6 -1.7004613056,51.1872856389,609.6 + + + + +
+ + EGRU113F BOSCOMBE RWY 05S + 510635N 0014909W -
510700N 0014941W -
510745N 0014817W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510720N 0014743W -
510635N 0014909W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8190288333,51.1098363889,609.6 -1.7952359444,51.12235775000001,609.6 -1.7986686484,51.1244440448,609.6 -1.8018536395,51.12668060710001,609.6 -1.8047743333,51.1290558056,609.6 -1.8281826944,51.11673549999999,609.6 -1.8190288333,51.1098363889,609.6 + + + + +
+ + EGRU113H BOSCOMBE RWY 17 + 511215N 0014526W -
511223N 0014436W -
511139N 0014419W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
511142N 0014513W -
511215N 0014526W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7572530278,51.20422258329999,609.6 -1.7536991944,51.1948913889,609.6 -1.7486860338,51.1949000253,609.6 -1.7436862295,51.1946701902,609.6 -1.7387285,51.1942031944,609.6 -1.743336,51.2063113333,609.6 -1.7572530278,51.20422258329999,609.6 + + + + +
+ + EGRU113I BOSCOMBE RWY 35 + 510608N 0014214W -
510600N 0014304W -
510656N 0014325W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510912N 0014504W to
510713N 0014238W -
510608N 0014214W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7037857778,51.1021631111,609.6 -1.7106696111,51.12032522220001,609.6 -1.7147495861,51.1185007217,609.6 -1.7190368393,51.1168755177,609.6 -1.7235068333,51.1154588889,609.6 -1.7176715,51.10007430560001,609.6 -1.7037857778,51.1021631111,609.6 + + + + +
+ + EGRU114A THRUXTON + A circle, 2 NM radius, centred at 511240N 0013549W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5969805556,51.2445019264,609.6 -1.6024346282,51.2443253397,609.6 -1.6078307621,51.2437974554,609.6 -1.6131116381,51.2429238812,609.6 -1.618221169,51.2417138962,609.6 -1.6231050988,51.24018035229999,609.6 -1.6277115819,51.23833953649999,609.6 -1.6319917356,51.2362109971,609.6 -1.6359001607,51.2338173351,609.6 -1.6393954239,51.2311839626,609.6 -1.6424404972,51.2283388323,609.6 -1.6450031492,51.2253121392,609.6 -1.6470562849,51.2221359992,609.6 -1.6485782301,51.21884410730001,609.6 -1.649552957,51.215471379,609.6 -1.64997025,51.21205357979999,609.6 -1.6498258088,51.2086269452,609.6 -1.6491212888,51.2052277961,609.6 -1.6478642784,51.2018921545,609.6 -1.6460682136,51.1986553617,609.6 -1.6437522304,51.1955517043,609.6 -1.6409409584,51.192614052,609.6 -1.637664256,51.1898735105,609.6 -1.6339568916,51.1873590929,609.6 -1.6298581736,51.1850974141,609.6 -1.6254115333,51.1831124099,609.6 -1.6206640652,51.18142508540001,609.6 -1.6156660294,51.1800532933,609.6 -1.6104703221,51.17901154670001,609.6 -1.6051319175,51.1783108659,609.6 -1.5997072902,51.1779586627,609.6 -1.5942538209,51.1779586627,609.6 -1.5888291937,51.1783108659,609.6 -1.5834907891,51.17901154670001,609.6 -1.5782950817,51.1800532933,609.6 -1.573297046,51.18142508540001,609.6 -1.5685495778,51.1831124099,609.6 -1.5641029375,51.1850974141,609.6 -1.5600042195,51.1873590929,609.6 -1.5562968551,51.1898735105,609.6 -1.5530201527,51.192614052,609.6 -1.5502088807,51.1955517043,609.6 -1.5478928975,51.1986553617,609.6 -1.5460968327,51.2018921545,609.6 -1.5448398223,51.2052277961,609.6 -1.5441353023,51.2086269452,609.6 -1.5439908611,51.21205357979999,609.6 -1.5444081541,51.215471379,609.6 -1.545382881,51.21884410730001,609.6 -1.5469048262,51.2221359992,609.6 -1.5489579619,51.2253121392,609.6 -1.5515206139,51.2283388323,609.6 -1.5545656872,51.2311839626,609.6 -1.5580609505,51.2338173351,609.6 -1.5619693756,51.2362109971,609.6 -1.5662495292,51.23833953649999,609.6 -1.5708560123,51.24018035229999,609.6 -1.5757399421,51.2417138962,609.6 -1.580849473,51.2429238812,609.6 -1.586130349,51.2437974554,609.6 -1.5915264829,51.2443253397,609.6 -1.5969805556,51.2445019264,609.6 + + + + +
+ + EGRU114B THRUXTON RWY 07 + 511117N 0013954W -
511147N 0014014W -
511209N 0013853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511139N 0013833W -
511117N 0013954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6649138889,51.1881222222,609.6 -1.6424814167,51.1941383889,609.6 -1.6447465308,51.19678413369999,609.6 -1.6466230757,51.1995473688,609.6 -1.6480957222,51.2024056111,609.6 -1.6705194444,51.19639166670001,609.6 -1.6649138889,51.1881222222,609.6 + + + + +
+ + EGRU114C THRUXTON RWY 25 + 511403N 0013144W -
511334N 0013124W -
511312N 0013245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511342N 0013305W -
511403N 0013144W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5288583333,51.2342861111,609.6 -1.5514453333,51.22825975,609.6 -1.5491841987,51.2256122627,609.6 -1.5473125872,51.22284753870001,609.6 -1.5458456667,51.21998811109999,609.6 -1.52325,51.2260166667,609.6 -1.5288583333,51.2342861111,609.6 + + + + +
+ + EGRU114D THRUXTON RWY 12 + 511357N 0014004W -
511424N 0013936W -
511354N 0013820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511326N 0013846W -
511357N 0014004W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6677805556,51.23258333330001,609.6 -1.6460598611,51.2237947222,609.6 -1.6440514429,51.2265260821,609.6 -1.6416583054,51.2291324058,609.6 -1.6388999444,51.2315923889,609.6 -1.6600138889,51.2401361111,609.6 -1.6677805556,51.23258333330001,609.6 + + + + +
+ + EGRU114E THRUXTON RWY 30 + 511116N 0013150W -
511048N 0013218W -
511118N 0013331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511240N 0013549W to
511144N 0013301W -
511116N 0013150W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Requests for permission to fly an unmanned aircraft are to be made to the Duty Operations Manager (Tel: 01264-772352 or Email: airtraffic@thruxtonairport.com). Requests are to be made at least 36 hours prior to the intended commencement of a flight.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5306666667,51.1876861111,609.6 -1.55016125,51.1956079444,609.6 -1.5525946413,51.193017224,609.6 -1.555389954,51.1905750191,609.6 -1.5585243611,51.18830125000001,609.6 -1.5384222222,51.1801333333,609.6 -1.5306666667,51.1876861111,609.6 + + + + +
+ + EGRU115A BRIZE NORTON + A circle, 2.5 NM radius, centred at 514500N 0013459W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5829472222,51.79159922819999,609.6 -1.5891388545,51.7914215516,609.6 -1.5952775171,51.790890042,609.6 -1.6013106972,51.7900092462,609.6 -1.6071867917,51.7887866989,609.6 -1.6128555517,51.7872328574,609.6 -1.6182685155,51.7853610116,609.6 -1.6233794253,51.7831871695,609.6 -1.6281446243,51.7807299195,609.6 -1.632523431,51.7780102697,609.6 -1.6364784872,51.7750514682,609.6 -1.6399760768,51.7718788023,609.6 -1.6429864125,51.7685193817,609.6 -1.6454838879,51.76500190580001,609.6 -1.6474472935,51.7613564176,609.6 -1.6488599943,51.7576140457,609.6 -1.6497100679,51.7538067388,609.6 -1.6499904014,51.7499669915,609.6 -1.6496987476,51.74612756720001,609.6 -1.6488377392,51.7423212184,609.6 -1.6474148615,51.7385804071,609.6 -1.6454423834,51.7349370286,609.6 -1.6429372489,51.7314221399,609.6 -1.6399209283,51.7280656959,609.6 -1.6364192318,51.72489629449999,609.6 -1.6324620865,51.7219409343,609.6 -1.6280832799,51.7192247855,609.6 -1.6233201699,51.7167709767,609.6 -1.618213367,51.71460039919999,609.6 -1.612806388,51.7127315299,609.6 -1.6071452871,51.7111802756,609.6 -1.6012782652,51.7099598381,609.6 -1.595255262,51.7090806028,609.6 -1.5891275342,51.7085500512,609.6 -1.5829472222,51.7083726977,609.6 -1.5767669102,51.7085500512,609.6 -1.5706391824,51.7090806028,609.6 -1.5646161793,51.7099598381,609.6 -1.5587491573,51.7111802756,609.6 -1.5530880564,51.7127315299,609.6 -1.5476810775,51.71460039919999,609.6 -1.5425742745,51.7167709767,609.6 -1.5378111646,51.7192247855,609.6 -1.5334323579,51.7219409343,609.6 -1.5294752127,51.72489629449999,609.6 -1.5259735161,51.7280656959,609.6 -1.5229571956,51.7314221399,609.6 -1.5204520611,51.7349370286,609.6 -1.518479583,51.7385804071,609.6 -1.5170567052,51.7423212184,609.6 -1.5161956968,51.74612756720001,609.6 -1.515904043,51.7499669915,609.6 -1.5161843765,51.7538067388,609.6 -1.5170344501,51.7576140457,609.6 -1.518447151,51.7613564176,609.6 -1.5204105566,51.76500190580001,609.6 -1.522908032,51.7685193817,609.6 -1.5259183676,51.7718788023,609.6 -1.5294159573,51.7750514682,609.6 -1.5333710135,51.7780102697,609.6 -1.5377498201,51.7807299195,609.6 -1.5425150191,51.7831871695,609.6 -1.5476259289,51.7853610116,609.6 -1.5530388928,51.7872328574,609.6 -1.5587076528,51.7887866989,609.6 -1.5645837472,51.7900092462,609.6 -1.5706169273,51.790890042,609.6 -1.5767555899,51.7914215516,609.6 -1.5829472222,51.79159922819999,609.6 + + + + +
+ + EGRU115B BRIZE NORTON RWY 07 + 514344N 0014017W -
514415N 0014032W -
514433N 0013856W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to
514402N 0013841W -
514344N 0014017W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6714538333,51.72900125,609.6 -1.6447841389,51.7339242778,609.6 -1.6464897503,51.736732361,609.6 -1.6478651552,51.7396094469,609.6 -1.6489031389,51.7425405833,609.6 -1.6755641667,51.7376190556,609.6 -1.6714538333,51.72900125,609.6 + + + + +
+ + EGRU115C BRIZE NORTON RWY 25 + 514615N 0012940W -
514544N 0012925W -
514527N 0013101W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 514500N 0013459W to
514558N 0013116W -
514615N 0012940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4943830556,51.77092427780001,609.6 -1.5210811389,51.7660371944,609.6 -1.5193796402,51.7632279118,609.6 -1.5180090481,51.7603498265,609.6 -1.5169764444,51.7574179167,609.6 -1.4902697222,51.7623065278,609.6 -1.4943830556,51.77092427780001,609.6 + + + + +
+ + EGRU116A MIDDLE WALLOP + A circle, 2 NM radius, centred at 510828N 0013422W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5726722222,51.17427732819999,609.6 -1.5781180062,51.1741007397,609.6 -1.5835059398,51.17357285,609.6 -1.5887787912,51.1726992668,609.6 -1.5938805588,51.1714892692,609.6 -1.5987570692,51.1699557093,609.6 -1.6033565558,51.16811487399999,609.6 -1.6076302102,51.165986312,609.6 -1.6115327024,51.1635926242,609.6 -1.6150226618,51.1609592229,609.6 -1.6180631166,51.1581140612,609.6 -1.6206218842,51.15508733410001,609.6 -1.6226719104,51.1519111579,609.6 -1.6241915537,51.14861922789999,609.6 -1.6251648102,51.14524646,609.6 -1.6255814795,51.1418286201,609.6 -1.6254372673,51.1384019438,609.6 -1.6247338262,51.135002753,609.6 -1.6234787327,51.13166706970001,609.6 -1.6216854019,51.12843023589999,609.6 -1.6193729405,51.1253265386,609.6 -1.6165659404,51.12238884820001,609.6 -1.6132942145,51.1196482706,609.6 -1.6095924784,51.1171338196,609.6 -1.6054999807,51.1148721104,609.6 -1.6010600869,51.1128870793,609.6 -1.59631982,51.11119973179999,609.6 -1.5913293643,51.1098279209,609.6 -1.5861415357,51.10878616000001,609.6 -1.5808112254,51.1080854694,609.6 -1.5753948227,51.1077332614,609.6 -1.5699496217,51.1077332614,609.6 -1.564533219,51.1080854694,609.6 -1.5592029088,51.10878616000001,609.6 -1.5540150801,51.1098279209,609.6 -1.5490246244,51.11119973179999,609.6 -1.5442843576,51.1128870793,609.6 -1.5398444637,51.1148721104,609.6 -1.535751966,51.1171338196,609.6 -1.5320502299,51.1196482706,609.6 -1.5287785041,51.12238884820001,609.6 -1.525971504,51.1253265386,609.6 -1.5236590426,51.12843023589999,609.6 -1.5218657117,51.13166706970001,609.6 -1.5206106182,51.135002753,609.6 -1.5199071771,51.1384019438,609.6 -1.5197629649,51.1418286201,609.6 -1.5201796342,51.14524646,609.6 -1.5211528908,51.14861922789999,609.6 -1.522672534,51.1519111579,609.6 -1.5247225603,51.15508733410001,609.6 -1.5272813278,51.1581140612,609.6 -1.5303217826,51.1609592229,609.6 -1.5338117421,51.1635926242,609.6 -1.5377142342,51.165986312,609.6 -1.5419878886,51.16811487399999,609.6 -1.5465873752,51.1699557093,609.6 -1.5514638856,51.1714892692,609.6 -1.5565656532,51.1726992668,609.6 -1.5618385047,51.17357285,609.6 -1.5672264383,51.1741007397,609.6 -1.5726722222,51.17427732819999,609.6 + + + + +
+ + EGRU116B MIDDLE WALLOP RWY 08 + 510812N 0013842W -
510844N 0013847W -
510849N 0013729W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510816N 0013731W -
510812N 0013842W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6450034167,51.1365355833,609.6 -1.6253642222,51.13786924999999,609.6 -1.6255978757,51.140904555,609.6 -1.6253905593,51.14394061749999,609.6 -1.6247439722,51.1469521389,609.6 -1.6465238611,51.14547324999999,609.6 -1.6450034167,51.1365355833,609.6 + + + + +
+ + EGRU116C MIDDLE WALLOP RWY 26 + 510922N 0012924W -
510849N 0012919W -
510842N 0013112W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510914N 0013126W -
510922N 0012924W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4901112778,51.15600175000001,609.6 -1.52378725,51.153753,609.6 -1.5221410871,51.1508959449,609.6 -1.5209162238,51.14795636429999,609.6 -1.5201227222,51.1449587778,609.6 -1.4885904722,51.1470641111,609.6 -1.4901112778,51.15600175000001,609.6 + + + + +
+ + EGRU116D MIDDLE WALLOP RWY 17 + 511125N 0013520W -
511129N 0013429W -
511027N 0013418W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
511024N 0013509W -
511125N 0013520W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.588953,51.19038572219999,609.6 -1.5857961667,51.1732382222,609.6 -1.5811173714,51.1738510424,609.6 -1.5763696609,51.1741960353,609.6 -1.5715917778,51.1742703889,609.6 -1.5747432222,51.1914171111,609.6 -1.588953,51.19038572219999,609.6 + + + + +
+ + EGRU116E MIDDLE WALLOP RWY 35 + 510530N 0013323W -
510526N 0013414W -
510628N 0013426W thence anti-clockwise by the arc of a circle radius 2 NM centred on 510828N 0013422W to
510631N 0013334W -
510530N 0013323W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.556427,51.0915795,609.6 -1.5595671111,51.1087266944,609.6 -1.5642396379,51.1081147689,609.6 -1.5689806823,51.10777029689999,609.6 -1.5737517222,51.1076960833,609.6 -1.5706061667,51.0905481111,609.6 -1.556427,51.0915795,609.6 + + + + +
+ + EGRU117A OXFORD + A circle, 2 NM radius, centred at 515013N 0011912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.32,51.8702344667,609.6 -1.3255294318,51.870057896,609.6 -1.3310001216,51.8695300599,609.6 -1.3363539553,51.8686565655,609.6 -1.3415340685,51.8674466918,609.6 -1.3464854536,51.86591329000001,609.6 -1.351155547,51.8640726463,609.6 -1.3554947899,51.861944308,609.6 -1.3594571558,51.8595508747,609.6 -1.3630006394,51.85691775719999,609.6 -1.3660877023,51.85407290610001,609.6 -1.3686856699,51.8510465145,609.6 -1.3707670754,51.8478706957,609.6 -1.3723099481,51.8445791419,609.6 -1.3732980424,51.84120676559999,609.6 -1.3737210051,51.8377893287,609.6 -1.3735744804,51.8343630631,609.6 -1.3728601504,51.8309642858,609.6 -1.371585712,51.8276290146,609.6 -1.3697647898,51.8243925863,609.6 -1.3674167871,51.8212892834,609.6 -1.3645666756,51.8183519709,609.6 -1.3612447278,51.8156117502,609.6 -1.3574861927,51.81309763019999,609.6 -1.3533309217,51.8108362217,609.6 -1.3488229448,51.8088514569,609.6 -1.3440100053,51.80716433740001,609.6 -1.3389430551,51.805792713,609.6 -1.3336757173,51.8047510943,609.6 -1.3282637222,51.8040504998,609.6 -1.3227643201,51.8036983402,609.6 -1.3172356799,51.8036983402,609.6 -1.3117362778,51.8040504998,609.6 -1.3063242827,51.8047510943,609.6 -1.3010569449,51.805792713,609.6 -1.2959899947,51.80716433740001,609.6 -1.2911770552,51.8088514569,609.6 -1.2866690783,51.8108362217,609.6 -1.2825138073,51.81309763019999,609.6 -1.2787552722,51.8156117502,609.6 -1.2754333244,51.8183519709,609.6 -1.2725832129,51.8212892834,609.6 -1.2702352102,51.8243925863,609.6 -1.268414288,51.8276290146,609.6 -1.2671398496,51.8309642858,609.6 -1.2664255196,51.8343630631,609.6 -1.2662789949,51.8377893287,609.6 -1.2667019576,51.84120676559999,609.6 -1.2676900519,51.8445791419,609.6 -1.2692329246,51.8478706957,609.6 -1.2713143301,51.8510465145,609.6 -1.2739122977,51.85407290610001,609.6 -1.2769993606,51.85691775719999,609.6 -1.2805428442,51.8595508747,609.6 -1.2845052101,51.861944308,609.6 -1.288844453,51.8640726463,609.6 -1.2935145464,51.86591329000001,609.6 -1.2984659315,51.8674466918,609.6 -1.3036460447,51.8686565655,609.6 -1.3089998784,51.8695300599,609.6 -1.3144705682,51.870057896,609.6 -1.32,51.8702344667,609.6 + + + + +
+ + EGRU117B OXFORD RWY 01 + 514710N 0011941W -
514716N 0012032W -
514819N 0012013W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to
514813N 0011922W -
514710N 0011941W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3280333333,51.7861444444,609.6 -1.3226977778,51.80369624999999,609.6 -1.3275216808,51.8039822011,609.6 -1.3322844625,51.8045363966,609.6 -1.3369474167,51.8053543333,609.6 -1.342275,51.78781111109999,609.6 -1.3280333333,51.7861444444,609.6 + + + + +
+ + EGRU117C OXFORD RWY 19 + 515316N 0011843W -
515310N 0011751W -
515207N 0011811W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515013N 0011912W to
515213N 0011902W -
515316N 0011843W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3118583333,51.8877833333,609.6 -1.3172211389,51.8701899722,609.6 -1.3123911033,51.8698993105,609.6 -1.3076231617,51.8693401192,609.6 -1.3029562222,51.8685169444,609.6 -1.2975861111,51.8861166667,609.6 -1.3118583333,51.8877833333,609.6 + + + + +
+ + EGRU118A BENSON + A circle, 2 NM radius, centred at 513654N 0010545W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0958472222,51.64833017530001,609.6 -1.1013496162,51.648153599,609.6 -1.1067935565,51.64762574589999,609.6 -1.112121214,51.64675222330001,609.6 -1.1172760033,51.6455423103,609.6 -1.1222031865,51.6440088582,609.6 -1.1268504575,51.64216815370001,609.6 -1.1311685001,51.6400397443,609.6 -1.1351115129,51.63764623010001,609.6 -1.1386376959,51.6350130224,609.6 -1.1417096938,51.6321680726,609.6 -1.1442949908,51.62914157429999,609.6 -1.1463662537,51.6259656419,609.6 -1.1479016182,51.62267396840001,609.6 -1.1488849166,51.6193014675,609.6 -1.1493058453,51.6158839024,609.6 -1.1491600683,51.61245750609999,609.6 -1.1484492582,51.6090585972,609.6 -1.1471810729,51.6057231948,609.6 -1.1453690692,51.60248663740001,609.6 -1.1430325547,51.5993832088,609.6 -1.1401963783,51.596445776,609.6 -1.1368906638,51.5937054416,609.6 -1.1331504879,51.5911912162,609.6 -1.1290155071,51.5889297119,609.6 -1.1245295367,51.5869448622,609.6 -1.1197400871,51.58525767,609.6 -1.1146978621,51.58388598620001,609.6 -1.109456224,51.5828443222,609.6 -1.1040706317,51.5821436971,609.6 -1.0985980574,51.581791522,609.6 -1.0930963871,51.581791522,609.6 -1.0876238127,51.5821436971,609.6 -1.0822382205,51.5828443222,609.6 -1.0769965823,51.58388598620001,609.6 -1.0719543573,51.58525767,609.6 -1.0671649077,51.5869448622,609.6 -1.0626789373,51.5889297119,609.6 -1.0585439565,51.5911912162,609.6 -1.0548037807,51.5937054416,609.6 -1.0514980662,51.596445776,609.6 -1.0486618898,51.5993832088,609.6 -1.0463253752,51.60248663740001,609.6 -1.0445133716,51.6057231948,609.6 -1.0432451862,51.6090585972,609.6 -1.0425343761,51.61245750609999,609.6 -1.0423885991,51.6158839024,609.6 -1.0428095278,51.6193014675,609.6 -1.0437928263,51.62267396840001,609.6 -1.0453281907,51.6259656419,609.6 -1.0473994536,51.62914157429999,609.6 -1.0499847507,51.6321680726,609.6 -1.0530567485,51.6350130224,609.6 -1.0565829315,51.63764623010001,609.6 -1.0605259443,51.6400397443,609.6 -1.064843987,51.64216815370001,609.6 -1.069491258,51.6440088582,609.6 -1.0744184411,51.6455423103,609.6 -1.0795732304,51.64675222330001,609.6 -1.084900888,51.64762574589999,609.6 -1.0903448282,51.648153599,609.6 -1.0958472222,51.64833017530001,609.6 + + + + +
+ + EGRU118B BENSON RWY 01 + 513342N 0010601W -
513347N 0010653W -
513459N 0010637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to
513454N 0010545W -
513342N 0010601W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1003111111,51.5617916667,609.6 -1.0959105556,51.5817474444,609.6 -1.100727273,51.5818864152,609.6 -1.1055043408,51.5822951597,609.6 -1.1102029444,51.5829703333,609.6 -1.1145972222,51.5630138889,609.6 -1.1003111111,51.5617916667,609.6 + + + + +
+ + EGRU118C BENSON RWY 19 + 514006N 0010529W -
514001N 0010437W -
513850N 0010453W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513654N 0010545W to
513854N 0010545W -
514006N 0010529W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0913722222,51.6682888889,609.6 -1.09578375,51.64833013890001,609.6 -1.0909598326,51.6481909345,609.6 -1.0861758008,51.6477815696,609.6 -1.0814706944,51.64710538889999,609.6 -1.0770527778,51.6670638889,609.6 -1.0913722222,51.6682888889,609.6 + + + + +
+ + EGRU119A CHALGROVE + A circle, 2 NM radius, centred at 514028N 0010507W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.08525,51.7078020585,609.6 -1.0907596062,51.7076254837,609.6 -1.0962106817,51.7070976351,609.6 -1.1015453216,51.7062241201,609.6 -1.1067068659,51.7050142177,609.6 -1.1116405047,51.7034807791,609.6 -1.1162938635,51.7016400909,609.6 -1.1206175612,51.69951170059999,609.6 -1.1245657363,51.69711820809999,609.6 -1.1280965342,51.6944850246,609.6 -1.1311725506,51.6916401013,609.6 -1.1337612274,51.6886136316,609.6 -1.1358351958,51.6854377297,609.6 -1.1373725631,51.68214608829999,609.6 -1.1383571408,51.6787736208,609.6 -1.1387786121,51.6753560901,609.6 -1.1386326357,51.67192972880001,609.6 -1.1379208867,51.6685308552,609.6 -1.1366510334,51.66519548800001,609.6 -1.1348366508,51.6619589652,609.6 -1.1324970718,51.6588555703,609.6 -1.1296571783,51.6559181698,609.6 -1.1263471336,51.6531778659,609.6 -1.1226020606,51.6506636687,609.6 -1.1184616675,51.6484021901,609.6 -1.113969827,51.6464173632,609.6 -1.1091741116,51.6447301904,609.6 -1.1041252912,51.6433585225,609.6 -1.0988767978,51.6423168707,609.6 -1.0934841627,51.6416162538,609.6 -1.0880044322,51.6412640828,609.6 -1.0824955678,51.6412640828,609.6 -1.0770158373,51.6416162538,609.6 -1.0716232022,51.6423168707,609.6 -1.0663747088,51.6433585225,609.6 -1.0613258884,51.6447301904,609.6 -1.056530173,51.6464173632,609.6 -1.0520383325,51.6484021901,609.6 -1.0478979394,51.6506636687,609.6 -1.0441528664,51.6531778659,609.6 -1.0408428217,51.6559181698,609.6 -1.0380029282,51.6588555703,609.6 -1.0356633492,51.6619589652,609.6 -1.0338489666,51.66519548800001,609.6 -1.0325791133,51.6685308552,609.6 -1.0318673643,51.67192972880001,609.6 -1.0317213879,51.6753560901,609.6 -1.0321428592,51.6787736208,609.6 -1.0331274369,51.68214608829999,609.6 -1.0346648042,51.6854377297,609.6 -1.0367387726,51.6886136316,609.6 -1.0393274494,51.6916401013,609.6 -1.0424034658,51.6944850246,609.6 -1.0459342637,51.69711820809999,609.6 -1.0498824388,51.69951170059999,609.6 -1.0542061365,51.7016400909,609.6 -1.0588594953,51.7034807791,609.6 -1.0637931341,51.7050142177,609.6 -1.0689546784,51.7062241201,609.6 -1.0742893183,51.7070976351,609.6 -1.0797403938,51.7076254837,609.6 -1.08525,51.7078020585,609.6 + + + + +
+ + EGRU120A ODIHAM + A circle, 2 NM radius, centred at 511403N 0005634W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9428083333,51.2674851282,609.6 -0.948265126,51.2673085421,609.6 -0.9536639509,51.26678065960001,609.6 -0.9589474603,51.2659070883,609.6 -0.9640595387999999,51.2646971075,609.6 -0.9689459033000001,51.26316356880001,609.6 -0.9735546824,51.26132275929999,609.6 -0.9778369687999999,51.2591942274,609.6 -0.9817473409,51.2568005738,609.6 -0.9852443446,51.2541672107,609.6 -0.9882909334999999,51.25132209069999,609.6 -0.9908548602,51.2482954088,609.6 -0.9929090162999999,51.2451192806,609.6 -0.9944317169,51.2418274011,609.6 -0.9954069262999999,51.2384546858,609.6 -0.9958244239999999,51.2350369,609.6 -0.9956799076000001,51.2316102789,609.6 -0.9949750335000001,51.2282111435,609.6 -0.9937173942,51.2248755156,609.6 -0.9919204321000001,51.2216387361,609.6 -0.9896032933000001,51.2185350918,609.6 -0.9867906194,51.215597452,609.6 -0.9835122839,51.2128569223,609.6 -0.9798030725,51.2103425156,609.6 -0.9757023133000001,51.2080808467,609.6 -0.971253459,51.20609585139999,609.6 -0.9665036277,51.2044085344,609.6 -0.9615031045,51.20303674849999,609.6 -0.9563048117,51.2019950066,609.6 -0.9509637509,51.2012943289,609.6 -0.9455364246,51.2009421274,609.6 -0.9400802421,51.2009421274,609.6 -0.9346529158000001,51.2012943289,609.6 -0.929311855,51.2019950066,609.6 -0.9241135621,51.20303674849999,609.6 -0.919113039,51.2044085344,609.6 -0.9143632076,51.20609585139999,609.6 -0.9099143534,51.2080808467,609.6 -0.9058135942,51.2103425156,609.6 -0.9021043827999999,51.2128569223,609.6 -0.8988260472999999,51.215597452,609.6 -0.8960133734,51.2185350918,609.6 -0.8936962345,51.2216387361,609.6 -0.8918992724999999,51.2248755156,609.6 -0.8906416331,51.2282111435,609.6 -0.8899367591,51.2316102789,609.6 -0.8897922427,51.2350369,609.6 -0.8902097403,51.2384546858,609.6 -0.8911849498,51.2418274011,609.6 -0.8927076503,51.2451192806,609.6 -0.8947618064999999,51.2482954088,609.6 -0.8973257331999999,51.25132209069999,609.6 -0.9003723221,51.2541672107,609.6 -0.9038693257999999,51.2568005738,609.6 -0.9077796979,51.2591942274,609.6 -0.9120619843,51.26132275929999,609.6 -0.9166707633,51.26316356880001,609.6 -0.9215571279,51.2646971075,609.6 -0.9266692064000001,51.2659070883,609.6 -0.9319527157,51.26678065960001,609.6 -0.9373515406999999,51.2673085421,609.6 -0.9428083333,51.2674851282,609.6 + + + + +
+ + EGRU120B ODIHAM RWY 09 + 511356N 0010140W -
511428N 0010137W -
511425N 0005942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to
511352N 0005944W -
511356N 0010140W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0277194444,51.2320944444,609.6 -0.9956238056,51.2311932778,609.6 -0.9958410277999998,51.23419482010001,609.6 -0.9956263240999998,51.2371964328,609.6 -0.9949813611000001,51.2401736667,609.6 -1.0270638889,51.241075,609.6 -1.0277194444,51.2320944444,609.6 + + + + +
+ + EGRU120C ODIHAM RWY 27 + 511410N 0005128W -
511338N 0005130W -
511341N 0005326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511403N 0005634W to
511414N 0005324W -
511410N 0005128W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8577777777999999,51.2362194444,609.6 -0.8899854444,51.2371621944,609.6 -0.889775671,51.2341610401,609.6 -0.8899976551,51.2311602307,609.6 -0.8906495,51.22818419439999,609.6 -0.8584305555999999,51.2272416667,609.6 -0.8577777777999999,51.2362194444,609.6 + + + + +
+ + EGRU121A BLACKBUSHE + 511738N 0005215W thence clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
511806N 0004829W -
511801N 0004919W -
511758N 0004954W -
511753N 0005038W -
511746N 0005120W -
511738N 0005215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8707499999999999,51.29395277780001,609.6 -0.8556861111000001,51.2962277778,609.6 -0.8438138889,51.29795,609.6 -0.8316222222,51.2993666667,609.6 -0.8219555556,51.3003611111,609.6 -0.8080277778,51.30159722220001,609.6 -0.8046211679,51.30423142349999,609.6 -0.8016523744000001,51.3070659151,609.6 -0.7991585751,51.3100749158,609.6 -0.7971657046,51.3132272484,609.6 -0.7956945203999999,51.3164902437,609.6 -0.7947603841999999,51.319830079,609.6 -0.7943730988,51.3232121275,609.6 -0.7945368009,51.3266013175,609.6 -0.7952499138,51.3299624951,609.6 -0.7965051585,51.3332607896,609.6 -0.7982896245,51.33646197549999,609.6 -0.8005848991000001,51.3395328276,609.6 -0.8033672544,51.3424414674,609.6 -0.8066078902000001,51.3451576942,609.6 -0.8102732304000001,51.3476533001,609.6 -0.8143252696,51.349902364,609.6 -0.8187219672000001,51.35188152210001,609.6 -0.8234176835000001,51.3535702113,609.6 -0.8283636551000001,51.3549508846,609.6 -0.833508503,51.35600919419999,609.6 -0.8387987690000001,51.35673414120001,609.6 -0.8441794738000001,51.3571181909,609.6 -0.8495946925,51.3571573517,609.6 -0.8549881386,51.3568512164,609.6 -0.8603037539999999,51.3562029671,609.6 -0.8654862942,51.3552193412,609.6 -0.8704819069,51.3539105616,609.6 -0.875238694,51.3522902294,609.6 -0.879707254,51.3503751817,609.6 -0.8838411967000001,51.34818531580001,609.6 -0.8875976263000002,51.34574338159999,609.6 -0.8909375871,51.3430747435,609.6 -0.8938264674000002,51.3402071163,609.6 -0.8962343572,51.33717027599999,609.6 -0.8981363562,51.3339957498,609.6 -0.8995128292,51.3307164872,609.6 -0.9003496056,51.3273665183,609.6 -0.9006381221999999,51.3239805991,609.6 -0.9003755074000002,51.3205938511,609.6 -0.8995646057,51.3172413967,609.6 -0.8982139433,51.3139579952,609.6 -0.8963376347000002,51.3107776825,609.6 -0.8939552325000001,51.307733419,609.6 -0.8910915201000001,51.30485674889999,609.6 -0.887776252,51.30217747420001,609.6 -0.8840438430999999,51.29972334679999,609.6 -0.8799330102,51.2975197822,609.6 -0.8754863704,51.2955895979,609.6 -0.8707499999999999,51.29395277780001,609.6 + + + + +
+ + EGRU121B BLACKBUSHE RWY 07 + 511815N 0005513W -
511845N 0005530W -
511904N 0005359W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
511834N 0005343W -
511815N 0005513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9204,51.30406388889999,609.6 -0.8952721667000001,51.3093216389,609.6 -0.8971743106000001,51.3120790247,609.6 -0.8986723185,51.31493262669999,609.6 -0.8997539444,51.3178592222,609.6 -0.9249277778,51.3125916667,609.6 -0.9204,51.30406388889999,609.6 + + + + +
+ + EGRU121C BLACKBUSHE RWY 25 + 512038N 0004631W -
512007N 0004614W -
511949N 0004743W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511926N 0005051W to
512019N 0004800W -
512038N 0004631W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7751972222000001,51.343825,609.6 -0.7998953611,51.3386891667,609.6 -0.7979607589,51.33594023149999,609.6 -0.7964298273,51.3330932315,609.6 -0.7953149722,51.3301713611,609.6 -0.7706638889,51.3352972222,609.6 -0.7751972222000001,51.343825,609.6 + + + + +
+ + EGRU122A WYCOMBE AIR PARK/BOOKER + A circle, 2 NM radius, centred at 513642N 0004830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8082305556,51.64502186089999,609.6 -0.8137325491000001,51.64484528449999,609.6 -0.8191760930999999,51.6443174311,609.6 -0.824503363,51.6434439081,609.6 -0.8296577772,51.6422339944,609.6 -0.8345846018999999,51.6407005416,609.6 -0.8392315348,51.6388598362,609.6 -0.8435492635,51.63673142580001,609.6 -0.8474919895999999,51.6343379104,609.6 -0.8510179164,51.6317047013,609.6 -0.8540896911,51.62885975,609.6 -0.8566748005000001,51.6258332502,609.6 -0.8587459132,51.62265731599999,609.6 -0.8602811664000001,51.6193656408,609.6 -0.8612643938000001,51.615993138,609.6 -0.8616852924000001,51.612575571,609.6 -0.8615395265,51.6091491728,609.6 -0.8608287685000001,51.6057502619,609.6 -0.8595606757000001,51.6024148575,609.6 -0.8577488041999999,51.5991782982,609.6 -0.8554124598,51.5960748678,609.6 -0.8525764897999999,51.5931374331,609.6 -0.8492710157,51.590397097,609.6 -0.8455311117999998,51.58788287,609.6 -0.8413964315,51.58562136430001,609.6 -0.8369107871,51.5836365134,609.6 -0.8321216853999999,51.58194932009999,609.6 -0.8270798266,51.58057763539999,609.6 -0.8218385692,51.57953597069999,609.6 -0.816453368,51.5788353451,609.6 -0.8109811909999999,51.57848316979999,609.6 -0.8054799201,51.57848316979999,609.6 -0.8000077430999999,51.5788353451,609.6 -0.7946225419999999,51.57953597069999,609.6 -0.7893812845,51.58057763539999,609.6 -0.7843394257,51.58194932009999,609.6 -0.7795503240000001,51.5836365134,609.6 -0.7750646795999999,51.58562136430001,609.6 -0.7709299992999999,51.58788287,609.6 -0.7671900954,51.590397097,609.6 -0.7638846213,51.5931374331,609.6 -0.7610486513,51.5960748678,609.6 -0.7587123069,51.5991782982,609.6 -0.7569004354000001,51.6024148575,609.6 -0.7556323426,51.6057502619,609.6 -0.7549215847000001,51.6091491728,609.6 -0.7547758187,51.612575571,609.6 -0.7551967173,51.615993138,609.6 -0.7561799447000001,51.6193656408,609.6 -0.7577151979999999,51.62265731599999,609.6 -0.7597863106,51.6258332502,609.6 -0.76237142,51.62885975,609.6 -0.7654431947,51.6317047013,609.6 -0.7689691215,51.6343379104,609.6 -0.7729118476,51.63673142580001,609.6 -0.7772295762999999,51.6388598362,609.6 -0.7818765092999999,51.6407005416,609.6 -0.7868033339,51.6422339944,609.6 -0.7919577480999999,51.6434439081,609.6 -0.797285018,51.6443174311,609.6 -0.802728562,51.64484528449999,609.6 -0.8082305556,51.64502186089999,609.6 + + + + +
+ + EGRU122B WYCOMBE AIR PARK/BOOKER RWY 06 + 513508N 0005225W -
513536N 0005249W -
513602N 0005131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513533N 0005107W -
513508N 0005225W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8734888889,51.58541944440001,609.6 -0.8518406944,51.5924746389,609.6 -0.8544514271,51.5950007053,609.6 -0.8566861956,51.59766302599999,609.6 -0.85852675,51.6004399444,609.6 -0.8801694444,51.5933861111,609.6 -0.8734888889,51.58541944440001,609.6 + + + + +
+ + EGRU122C WYCOMBE AIR PARK/BOOKER RWY 24 + 513817N 0004434W -
513748N 0004410W -
513723N 0004529W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513752N 0004553W -
513817N 0004434W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7428694443999999,51.63803055559999,609.6 -0.7645970833,51.63098213890001,609.6 -0.7619873992000001,51.6284546928,609.6 -0.7597547123,51.6257910769,609.6 -0.7579171667,51.623013,609.6 -0.7361805556000001,51.6300638889,609.6 -0.7428694443999999,51.63803055559999,609.6 + + + + +
+ + EGRU122D WYCOMBE AIR PARK/BOOKER RWY 06G + 513506N 0005218W -
513535N 0005242W -
513559N 0005129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513531N 0005104W -
513506N 0005218W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8717527777999999,51.58513333329999,609.6 -0.8511163333,51.591854,609.6 -0.8538205929,51.5943427601,609.6 -0.8561537856000001,51.5969732224,609.6 -0.8580968611000001,51.5997239722,609.6 -0.8784277778,51.5931027778,609.6 -0.8717527777999999,51.58513333329999,609.6 + + + + +
+ + EGRU122E WYCOMBE AIR PARK/BOOKER RWY 24G + 513814N 0004433W -
513746N 0004408W -
513720N 0004527W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513749N 0004550W -
513814N 0004433W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7423638889,51.6373111111,609.6 -0.7638803889,51.6303364444,609.6 -0.7613668981000001,51.62777105100001,609.6 -0.7592355649,51.6250750191,609.6 -0.7575036944,51.6222703333,609.6 -0.7356805556,51.6293444444,609.6 -0.7423638889,51.6373111111,609.6 + + + + +
+ + EGRU122G WYCOMBE AIR PARK/BOOKER RWY 35 + 513351N 0004703W -
513344N 0004754W -
513443N 0004815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513642N 0004830W to
513450N 0004724W -
513351N 0004703W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7843015278,51.5641660833,609.6 -0.7899565833000001,51.58044494439999,609.6 -0.7945577485999999,51.5795466346,609.6 -0.7992699984,51.5789101889,609.6 -0.8040550556,51.5785408056,609.6 -0.798395,51.562262,609.6 -0.7843015278,51.5641660833,609.6 + + + + +
+ + EGRU123A FARNBOROUGH + 511758N 0004954W -
511801N 0004919W -
511806N 0004829W -
511812N 0004723W -
511817N 0004705W -
511851N 0004551W -
511856N 0004537W thence clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to -
511758N 0004954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8316222222,51.2993666667,609.6 -0.8349233580999998,51.2961419297,609.6 -0.8377383331,51.2927409314,609.6 -0.8400421018999999,51.2891919749,609.6 -0.8418152365,51.2855251742,609.6 -0.8430428226,51.2817716363,609.6 -0.843714583,51.2779631961,609.6 -0.8438249598000001,51.2741321464,609.6 -0.8433731571,51.2703109638,609.6 -0.842363143,51.2665320331,609.6 -0.8408036111,51.2628273734,609.6 -0.8387079028,51.2592283667,609.6 -0.8360938895,51.2557654929,609.6 -0.8329838181,51.2524680725,609.6 -0.8294041189999999,51.2493640189,609.6 -0.8253851800999999,51.2464796031,609.6 -0.8209610875,51.2438392327,609.6 -0.8161693361,51.24146524609999,609.6 -0.8110505121,51.2393777248,609.6 -0.8056479499,51.2375943248,609.6 -0.8000073667000001,51.2361301276,609.6 -0.7941764778,51.23499751429999,609.6 -0.7882045952,51.23420606129999,609.6 -0.7821422136,51.23376246,609.6 -0.7760405870000001,51.23367046079999,609.6 -0.7699512981,51.2339308414,609.6 -0.7639258263000001,51.23454140050001,609.6 -0.758015116,51.23549697630001,609.6 -0.7522691488,51.2367894894,609.6 -0.7467365243,51.238408011,609.6 -0.7414640514999999,51.2403388547,609.6 -0.7364963554,51.2425656908,609.6 -0.7318755007,51.2450696839,609.6 -0.7276406369,51.2478296513,609.6 -0.7238276671,51.2508222408,609.6 -0.7204689437,51.25402212709999,609.6 -0.7175929929,51.2574022255,609.6 -0.7152242708999998,51.2609339197,609.6 -0.7133829545,51.2645873035,609.6 -0.7120847663999998,51.2683314329,609.6 -0.7113408381000002,51.2721345878,609.6 -0.7111576111000001,51.2759645403,609.6 -0.7115367784,51.2797888272,609.6 -0.7124752643999999,51.2835750257,609.6 -0.7139652472,51.2872910278,609.6 -0.7159942199,51.290905313,609.6 -0.7185450923999999,51.2943872168,609.6 -0.7215963328999999,51.29770719070001,609.6 -0.725122147,51.3008370544,609.6 -0.729092694,51.3037502357,609.6 -0.7334743386,51.3064219971,609.6 -0.7382299347,51.3088296472,609.6 -0.7433191407,51.3109527342,609.6 -0.7486987625999999,51.3127732211,609.6 -0.7543231217,51.3142756395,609.6 -0.7601444444,51.3154472222,609.6 -0.7641027777999999,51.3140444444,609.6 -0.7846027778,51.30463888890001,609.6 -0.7897027778,51.3033833333,609.6 -0.8080277778,51.30159722220001,609.6 -0.8219555556,51.3003611111,609.6 -0.8316222222,51.2993666667,609.6 + + + + +
+ + EGRU123B FARNBOROUGH RWY 06 + 511452N 0005042W -
511521N 0005107W -
511536N 0005021W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to
511507N 0004957W -
511452N 0005042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8450972222000001,51.24775833330001,609.6 -0.8324629166999999,51.25197830559999,609.6 -0.8349976079,51.2545235792,609.6 -0.8372336199,51.2571768339,609.6 -0.8391593056,51.2599242778,609.6 -0.8518138889,51.2556972222,609.6 -0.8450972222000001,51.24775833330001,609.6 + + + + +
+ + EGRU123C FARNBOROUGH RWY 24 + 511811N 0004233W -
511743N 0004209W -
511727N 0004257W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511631N 0004639W to
511755N 0004322W -
511811N 0004233W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.709275,51.3031861111,609.6 -0.7226773611000001,51.2987325,609.6 -0.7201248588999999,51.2961928717,609.6 -0.717871246,51.2935444601,609.6 -0.7159282222,51.2908010556,609.6 -0.7025472222,51.2952472222,609.6 -0.709275,51.3031861111,609.6 + + + + +
+ + EGRU124A WHITE WALTHAM + A circle, 2 NM radius, centred at 513002N 0004629W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7748333333,51.53395027229999,609.6 -0.7803219262,51.5337736931,609.6 -0.7857522123,51.5332458312,609.6 -0.7910665085,51.532372294,609.6 -0.7962083715,51.53116236060001,609.6 -0.801123201,51.5296288826,609.6 -0.8057588225,51.5277881466,609.6 -0.8100660436,51.5256597005,609.6 -0.8139991778,51.5232661445,609.6 -0.8175165298000001,51.52063289029999,609.6 -0.8205808377,51.5177878894,609.6 -0.8231596670999999,51.5147613361,609.6 -0.8252257528000001,51.5115853449,609.6 -0.8267572846,51.5082936097,609.6 -0.827738135,51.5049210445,609.6 -0.8281580254000001,51.5015034131,609.6 -0.8280126299,51.49807694940001,609.6 -0.8273036164000001,51.4946779725,609.6 -0.8260386228,51.4913425024,609.6 -0.8242311716,51.4881058784,609.6 -0.821900521,51.4850023851,609.6 -0.8190714576,51.48206489010001,609.6 -0.8157740292999999,51.4793244971,609.6 -0.8120432247,51.4768102173,609.6 -0.807918601,51.4745486636,609.6 -0.8034438637,51.47256377010001,609.6 -0.7986664044,51.4708765405,609.6 -0.7936368002999998,51.469504826,609.6 -0.7884082803999999,51.4684631386,609.6 -0.7830361654,51.4677624977,609.6 -0.7775772851,51.4674103147,609.6 -0.7720893814999999,51.4674103147,609.6 -0.7666305013,51.4677624977,609.6 -0.7612583862999999,51.4684631386,609.6 -0.7560298663999999,51.469504826,609.6 -0.7510002622999999,51.4708765405,609.6 -0.746222803,51.47256377010001,609.6 -0.7417480657,51.4745486636,609.6 -0.7376234419,51.4768102173,609.6 -0.7338926373999999,51.4793244971,609.6 -0.7305952091,51.48206489010001,609.6 -0.7277661456,51.4850023851,609.6 -0.7254354951000002,51.4881058784,609.6 -0.7236280438,51.4913425024,609.6 -0.7223630502,51.4946779725,609.6 -0.7216540366999999,51.49807694940001,609.6 -0.7215086413000001,51.5015034131,609.6 -0.7219285317,51.5049210445,609.6 -0.7229093821,51.5082936097,609.6 -0.7244409138999999,51.5115853449,609.6 -0.7265069995000001,51.5147613361,609.6 -0.729085829,51.5177878894,609.6 -0.7321501369,51.52063289029999,609.6 -0.7356674889,51.5232661445,609.6 -0.7396006231,51.5256597005,609.6 -0.7439078442,51.5277881466,609.6 -0.7485434657000001,51.5296288826,609.6 -0.7534582952,51.53116236060001,609.6 -0.7586001581000001,51.532372294,609.6 -0.7639144543,51.5332458312,609.6 -0.7693447405000001,51.5337736931,609.6 -0.7748333333,51.53395027229999,609.6 + + + + +
+ + EGRU124B WHITE WALTHAM RWY 03 + 512712N 0004802W -
512727N 0004848W -
512819N 0004807W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512807N 0004719W -
512712N 0004802W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8004888889,51.4534388889,609.6 -0.7886194722000001,51.4684981389,609.6 -0.7932141706999999,51.4694066717,609.6 -0.7976589203,51.4705705112,609.6 -0.8019174443999999,51.4719801667,609.6 -0.8133944444,51.4574138889,609.6 -0.8004888889,51.4534388889,609.6 + + + + +
+ + EGRU124C WHITE WALTHAM RWY 21 + 513247N 0004436W -
513233N 0004349W -
513137N 0004433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513154N 0004518W -
513247N 0004436W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7432027778,51.5463361111,609.6 -0.7549029443999999,51.5315407778,609.6 -0.7505130261,51.5302910944,609.6 -0.746322272,51.5287990749,609.6 -0.7423649722,51.52707694440001,609.6 -0.7302722222,51.54236388889999,609.6 -0.7432027778,51.5463361111,609.6 + + + + +
+ + EGRU124D WHITE WALTHAM RWY 07 + 512831N 0005037W -
512900N 0005059W -
512926N 0004932W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512857N 0004910W -
512831N 0005037W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8435944444000001,51.4752861111,609.6 -0.8194776388999999,51.482447,609.6 -0.8219270335,51.4850334633,609.6 -0.8239931833,51.4877472443,609.6 -0.8256592222,51.49056625,609.6 -0.8497666667,51.4834083333,609.6 -0.8435944444000001,51.4752861111,609.6 + + + + +
+ + EGRU124E WHITE WALTHAM RWY 25 + 513134N 0004222W -
513104N 0004159W -
513039N 0004326W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513108N 0004349W -
513134N 0004222W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7060083333,51.52598611110001,609.6 -0.7301535555999999,51.51885275,609.6 -0.7277079881000001,51.51626487040001,609.6 -0.7256465230999999,51.5135499515,609.6 -0.7239859167,51.5107301111,609.6 -0.6998305556,51.5178666667,609.6 -0.7060083333,51.52598611110001,609.6 + + + + +
+ + EGRU124F WHITE WALTHAM RWY 11 + 513039N 0005100W -
513109N 0005042W -
513052N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
513020N 0004939W -
513039N 0005100W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8499277778000001,51.51070833329999,609.6 -0.8275694999999998,51.5056710833,609.6 -0.8266300624,51.50862355649999,609.6 -0.8252669632,51.5115109942,609.6 -0.8234912778,51.5143097778,609.6 -0.8450222222,51.51916111109999,609.6 -0.8499277778000001,51.51070833329999,609.6 + + + + +
+ + EGRU124G WHITE WALTHAM RWY 29 + 512909N 0004152W -
512839N 0004210W -
512900N 0004345W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513002N 0004629W to
512930N 0004324W -
512909N 0004152W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6978833333,51.4859083333,609.6 -0.7234618056,51.49170572220001,609.6 -0.724968234,51.4888470135,609.6 -0.7268817969,51.48608487589999,609.6 -0.7291868056,51.4834418611,609.6 -0.7027833333,51.4774583333,609.6 -0.6978833333,51.4859083333,609.6 + + + + +
+ + EGRU125A HALTON + A circle, 2 NM radius, centred at 514732N 0004411W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.73645,51.8255736098,609.6 -0.7419739621,51.825397038,609.6 -0.7474392404,51.8248691985,609.6 -0.7527877787000001,51.8239956984,609.6 -0.7579627689000001,51.8227858168,609.6 -0.7629092579,51.8212524049,609.6 -0.7675747342999999,51.819411749,609.6 -0.7719096884999999,51.8172833964,609.6 -0.7758681392,51.8148899469,609.6 -0.7794081229000001,51.8122568112,609.6 -0.7824921382000001,51.8094119403,609.6 -0.7850875426,51.8063855272,609.6 -0.7871668962,51.80320968560001,609.6 -0.78870825,51.7999181077,609.6 -0.7896953741,51.79654570630001,609.6 -0.7901179254,51.7931282437,609.6 -0.789971552,51.7897019518,609.6 -0.7892579341,51.786303148,609.6 -0.7879847607,51.7829678504,609.6 -0.7861656427,51.7797313962,609.6 -0.7838199640999999,51.77662806789999,609.6 -0.7809726717,51.77369073130001,609.6 -0.7776540078,51.77095048769999,609.6 -0.7738991868,51.7684363465,609.6 -0.7697480205000001,51.7661749187,609.6 -0.7652444955,51.76419013690001,609.6 -0.7604363079999998,51.76250300269999,609.6 -0.7553743596,51.76113136639999,609.6 -0.7501122209,51.7600897386,609.6 -0.744705567,51.7593891379,609.6 -0.7392115921,51.75903697510001,609.6 -0.7336884078999999,51.75903697510001,609.6 -0.728194433,51.7593891379,609.6 -0.7227877791,51.7600897386,609.6 -0.7175256403999999,51.76113136639999,609.6 -0.712463692,51.76250300269999,609.6 -0.7076555045,51.76419013690001,609.6 -0.7031519795,51.7661749187,609.6 -0.6990008132,51.7684363465,609.6 -0.6952459922000001,51.77095048769999,609.6 -0.6919273283,51.77369073130001,609.6 -0.6890800359,51.77662806789999,609.6 -0.6867343573,51.7797313962,609.6 -0.6849152393,51.7829678504,609.6 -0.6836420659,51.786303148,609.6 -0.682928448,51.7897019518,609.6 -0.6827820746,51.7931282437,609.6 -0.6832046259,51.79654570630001,609.6 -0.68419175,51.7999181077,609.6 -0.6857331038,51.80320968560001,609.6 -0.6878124574,51.8063855272,609.6 -0.6904078618,51.8094119403,609.6 -0.6934918771,51.8122568112,609.6 -0.6970318608,51.8148899469,609.6 -0.7009903115,51.8172833964,609.6 -0.7053252657,51.819411749,609.6 -0.7099907421,51.8212524049,609.6 -0.7149372311000001,51.8227858168,609.6 -0.7201122213,51.8239956984,609.6 -0.7254607596,51.8248691985,609.6 -0.7309260378999999,51.825397038,609.6 -0.73645,51.8255736098,609.6 + + + + +
+ + EGRU125B HALTON RWY 02 + 514440N 0004521W -
514451N 0004610W -
514546N 0004539W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514535N 0004450W -
514440N 0004521W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7558487222,51.7445320556,609.6 -0.7472673332999999,51.7596761944,609.6 -0.7519601648000002,51.76041354200001,609.6 -0.7565269625,51.7614102361,609.6 -0.7609306111,51.76265816669999,609.6 -0.7695065,51.7475157222,609.6 -0.7558487222,51.7445320556,609.6 + + + + +
+ + EGRU125C HALTON RWY 20 + 515024N 0004301W -
515013N 0004212W -
514919N 0004243W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514930N 0004332W -
515024N 0004301W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7170164999999999,51.8400288889,609.6 -0.7256216944,51.8248898889,609.6 -0.7209224785000001,51.82415175580001,609.6 -0.7163499724000001,51.8231539352,609.6 -0.7119414722,51.8219045833,609.6 -0.7033307222,51.83704525,609.6 -0.7170164999999999,51.8400288889,609.6 + + + + +
+ + EGRU125D HALTON RWY 07 + 514615N 0004829W -
514646N 0004846W -
514705N 0004719W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514635N 0004701W -
514615N 0004829W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8080578056,51.7708836389,609.6 -0.78350425,51.7762662222,609.6 -0.7856425451,51.7789628325,609.6 -0.7873803361,51.781768038,609.6 -0.7887033889,51.784659,609.6 -0.8128740833000001,51.77936019440001,609.6 -0.8080578056,51.7708836389,609.6 + + + + +
+ + EGRU125E HALTON RWY 25 + 514840N 0004002W -
514810N 0003944W -
514753N 0004101W thence anti-clockwise by the arc of a circle radius 2 NM centred on 514732N 0004411W to
514824N 0004117W -
514840N 0004002W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6671238889,51.8112181389,609.6 -0.6880245278,51.8066635556,609.6 -0.6861315652,51.803896992,609.6 -0.6846489466,51.8010358551,609.6 -0.6835886944,51.7981034722,609.6 -0.6623042222,51.8027416389,609.6 -0.6671238889,51.8112181389,609.6 + + + + +
+ + EGRU126A FAIROAKS + A circle, 2 NM radius, centred at 512053N 0003331W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5587083333,51.3813205885,609.6 -0.5641786514,51.3811440053,609.6 -0.5695908575999999,51.3806161316,609.6 -0.5748874614,51.37974257490001,609.6 -0.580012208,51.3785326144,609.6 -0.5849106794,51.3769991016,609.6 -0.5895308752,51.3751583236,609.6 -0.5938237669999999,51.37302982840001,609.6 -0.5977438204,51.3706362166,609.6 -0.6012494788,51.3680029,609.6 -0.604303604,51.3651578309,609.6 -0.6068738693,51.36213120399999,609.6 -0.6089330994,51.3589551344,609.6 -0.6104595561,51.3556633166,609.6 -0.6114371648,51.35229066549999,609.6 -0.6118556802,51.34887294570001,609.6 -0.6117107899999999,51.3454463918,609.6 -0.6110041553,51.3420473242,609.6 -0.6097433881,51.33871176369999,609.6 -0.6079419646999999,51.3354750507,609.6 -0.605619079,51.33237147089999,609.6 -0.6027994342,51.32943389300001,609.6 -0.5995129781,51.32669342169999,609.6 -0.5957945826,51.3241790693,609.6 -0.5916836731,51.3219174496,609.6 -0.5872238101,51.31993249780001,609.6 -0.5824622279,51.3182452181,609.6 -0.5774493358,51.3168734627,609.6 -0.5722381866,51.3158317441,609.6 -0.5668839175,51.3151310822,609.6 -0.5614431705,51.3147788885,609.6 -0.5559734962,51.3147788885,609.6 -0.5505327491000001,51.3151310822,609.6 -0.5451784801,51.3158317441,609.6 -0.5399673309,51.3168734627,609.6 -0.5349544388,51.3182452181,609.6 -0.5301928566,51.31993249780001,609.6 -0.5257329936,51.3219174496,609.6 -0.5216220841,51.3241790693,609.6 -0.5179036886,51.32669342169999,609.6 -0.5146172324,51.32943389300001,609.6 -0.5117975876999999,51.33237147089999,609.6 -0.5094747019,51.3354750507,609.6 -0.5076732786,51.33871176369999,609.6 -0.5064125113,51.3420473242,609.6 -0.5057058767,51.3454463918,609.6 -0.5055609864,51.34887294570001,609.6 -0.5059795018,51.35229066549999,609.6 -0.5069571105,51.3556633166,609.6 -0.5084835673,51.3589551344,609.6 -0.5105427974,51.36213120399999,609.6 -0.5131130626,51.3651578309,609.6 -0.5161671879,51.3680029,609.6 -0.5196728463,51.3706362166,609.6 -0.5235928997,51.37302982840001,609.6 -0.5278857915,51.3751583236,609.6 -0.5325059873,51.3769991016,609.6 -0.5374044587,51.3785326144,609.6 -0.5425292053,51.37974257490001,609.6 -0.5478258091,51.3806161316,609.6 -0.5532380153000001,51.3811440053,609.6 -0.5587083333,51.3813205885,609.6 + + + + +
+ + EGRU126B FAIROAKS RWY 06 + 511907N 0003712W -
511934N 0003739W -
512003N 0003626W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to
511936N 0003558W -
511907N 0003712W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6199333333,51.318625,609.6 -0.5994920556,51.3266777222,609.6 -0.6023993034,51.3290671078,609.6 -0.6049511893,51.33161090240001,609.6 -0.6071268889,51.3342884167,609.6 -0.6275583333,51.3262388889,609.6 -0.6199333333,51.318625,609.6 + + + + +
+ + EGRU126C FAIROAKS RWY 24 + 512239N 0002949W -
512212N 0002922W -
512142N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to
512210N 0003104W -
512239N 0002949W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4969416667,51.37758888890001,609.6 -0.5178943056,51.3693692222,609.6 -0.5149878589,51.3669779903,609.6 -0.5124379479,51.3644324142,609.6 -0.5102653056000001,51.36175325,609.6 -0.4893055556,51.369975,609.6 -0.4969416667,51.37758888890001,609.6 + + + + +
+ + EGRU127A DENHAM + A circle, 2 NM radius, centred at 513518N 0003047W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5129944444,51.6217164382,609.6 -0.5184936191,51.62153986119999,609.6 -0.5239343742,51.621012006,609.6 -0.5292589149,51.6201384801,609.6 -0.5344106889,51.6189285623,609.6 -0.5393349903,51.6173951042,609.6 -0.5439795438,51.6155543924,609.6 -0.5482950621,51.6134259744,609.6 -0.5522357706,51.6110324506,609.6 -0.5557598936,51.608399232,609.6 -0.5588300976,51.60555427029999,609.6 -0.5614138859,51.60252775930001,609.6 -0.5634839411,51.5993518132,609.6 -0.5650184115,51.59606012529999,609.6 -0.5660011389,51.5926876095,609.6 -0.5664218254,51.589270029,609.6 -0.5662761375000001,51.585843617,609.6 -0.5655657464,51.5824446922,609.6 -0.5642983056999999,51.57910927410001,609.6 -0.5624873639,51.57587270119999,609.6 -0.5601522173,51.5727692576,609.6 -0.5573177001,51.5698318103,609.6 -0.5540139185,51.5670914623,609.6 -0.5502759287,51.56457722420001,609.6 -0.5461433639,51.56231570839999,609.6 -0.5416600139,51.56033084849999,609.6 -0.5368733613,51.55864364759999,609.6 -0.5318340803,51.5572719567,609.6 -0.5265955023,51.5562302872,609.6 -0.5212130538999999,51.5555296584,609.6 -0.5157436739,51.5551774815,609.6 -0.510245215,51.5551774815,609.6 -0.504775835,51.5555296584,609.6 -0.4993933866,51.5562302872,609.6 -0.4941548086,51.5572719567,609.6 -0.4891155276,51.55864364759999,609.6 -0.484328875,51.56033084849999,609.6 -0.4798455249,51.56231570839999,609.6 -0.4757129602,51.56457722420001,609.6 -0.4719749703,51.5670914623,609.6 -0.4686711888000001,51.5698318103,609.6 -0.4658366715999999,51.5727692576,609.6 -0.4635015249,51.57587270119999,609.6 -0.4616905832,51.57910927410001,609.6 -0.4604231424,51.5824446922,609.6 -0.4597127514,51.585843617,609.6 -0.4595670635,51.589270029,609.6 -0.4599877499,51.5926876095,609.6 -0.4609704774,51.59606012529999,609.6 -0.4625049477,51.5993518132,609.6 -0.464575003,51.60252775930001,609.6 -0.4671587913,51.60555427029999,609.6 -0.4702289953,51.608399232,609.6 -0.4737531183000001,51.6110324506,609.6 -0.4776938267,51.6134259744,609.6 -0.4820093451,51.6155543924,609.6 -0.4866538986,51.6173951042,609.6 -0.4915782,51.6189285623,609.6 -0.4967299739,51.6201384801,609.6 -0.5020545147,51.621012006,609.6 -0.5074952698,51.62153986119999,609.6 -0.5129944444,51.6217164382,609.6 + + + + +
+ + EGRU127B DENHAM RWY 06 + 513336N 0003432W -
513404N 0003459W -
513431N 0003344W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513404N 0003317W -
513336N 0003432W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5756055556,51.5599277778,609.6 -0.5547771667,51.56767425,609.6 -0.5576101111,51.57010516770001,609.6 -0.5600801312,51.5726852958,609.6 -0.5621670833,51.5753936389,609.6 -0.5829861111,51.56765,609.6 -0.5756055556,51.5599277778,609.6 + + + + +
+ + EGRU127C DENHAM RWY 24 + 513700N 0002704W -
513632N 0002637W -
513605N 0002750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513633N 0002816W -
513700N 0002704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.450975,51.6166444444,609.6 -0.4711767778000001,51.60916325,609.6 -0.4683454518999999,51.6067302115,609.6 -0.4658782366,51.6041480831,609.6 -0.4637951944,51.6014379167,609.6 -0.4435833333,51.6089222222,609.6 -0.450975,51.6166444444,609.6 + + + + +
+ + EGRU127D DENHAM RWY 12 + 513623N 0003455W -
513652N 0003431W -
513629N 0003322W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513600N 0003347W -
513623N 0003455W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5820527778,51.6064472222,609.6 -0.5630313056,51.6001324167,609.6 -0.5611342148,51.6028946338,609.6 -0.5588447291,51.6055390603,609.6 -0.5561814443999999,51.6080441389,609.6 -0.57525,51.61437500000001,609.6 -0.5820527778,51.6064472222,609.6 + + + + +
+ + EGRU127E DENHAM RWY 30 + 513416N 0002641W -
513347N 0002706W -
513409N 0002810W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513437N 0002746W -
513416N 0002641W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4448222222000001,51.57097499999999,609.6 -0.4628163333,51.57697613890001,609.6 -0.464678404,51.5742051095,609.6 -0.4669335187,51.5715499091,609.6 -0.4695632778,51.5690321389,609.6 -0.4516166667,51.5630472222,609.6 -0.4448222222000001,51.57097499999999,609.6 + + + + +
+ + EGRU128A LONDON HEATHROW + A circle, 2.5 NM radius, centred at 512839N 0002741W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.46135,51.519198392,609.6 -0.4675046258,51.5190207088,609.6 -0.4736065998,51.5184891791,609.6 -0.4796037246,51.51760834980001,609.6 -0.4854447065999999,51.5163857558,609.6 -0.4910795983,51.5148318544,609.6 -0.4964602286,51.51295993590001,609.6 -0.5015406165,51.5107860084,609.6 -0.5062773666,51.50832866060001,609.6 -0.5106300405,51.5056089011,609.6 -0.5145615031,51.5026499783,609.6 -0.5180382389,51.49947718029999,609.6 -0.5210306378,51.4961176176,609.6 -0.5235132452,51.4925999902,609.6 -0.5254649770000001,51.4889543421,609.6 -0.526869296,51.4852118033,609.6 -0.5277143491,51.48140432329999,609.6 -0.5279930642,51.47756439840001,609.6 -0.5277032055999999,51.4737247933,609.6 -0.5268473884,51.4699182621,609.6 -0.5254330514,51.46617726860001,609.6 -0.5234723888,51.46253370969999,609.6 -0.5209822419,51.4590186443,609.6 -0.5179839515,51.4556620291,609.6 -0.5145031729,51.4524924637,609.6 -0.510569654,51.4495369488,609.6 -0.5062169801,51.4468206561,609.6 -0.5014822864,51.4443667159,609.6 -0.4964059411,51.4421960211,609.6 -0.4910312023,51.4403270501,609.6 -0.4854038501,51.4387757108,609.6 -0.479571799,51.4375552059,609.6 -0.4735846922,51.436675922,609.6 -0.4674934822,51.436145341,609.6 -0.46135,51.43596797760001,609.6 -0.4552065178,51.436145341,609.6 -0.4491153078,51.436675922,609.6 -0.443128201,51.4375552059,609.6 -0.4372961499,51.4387757108,609.6 -0.4316687977,51.4403270501,609.6 -0.4262940589,51.4421960211,609.6 -0.4212177136,51.4443667159,609.6 -0.4164830199,51.4468206561,609.6 -0.412130346,51.4495369488,609.6 -0.4081968271,51.4524924637,609.6 -0.4047160485,51.4556620291,609.6 -0.4017177581,51.4590186443,609.6 -0.3992276111999999,51.46253370969999,609.6 -0.3972669486000001,51.46617726860001,609.6 -0.3958526116,51.4699182621,609.6 -0.3949967944000001,51.4737247933,609.6 -0.3947069358,51.47756439840001,609.6 -0.3949856508999999,51.48140432329999,609.6 -0.395830704,51.4852118033,609.6 -0.3972350230000001,51.4889543421,609.6 -0.3991867548,51.4925999902,609.6 -0.4016693622,51.4961176176,609.6 -0.4046617611,51.49947718029999,609.6 -0.4081384969,51.5026499783,609.6 -0.4120699595000001,51.5056089011,609.6 -0.4164226334,51.50832866060001,609.6 -0.4211593835,51.5107860084,609.6 -0.4262397714,51.51295993590001,609.6 -0.4316204017,51.5148318544,609.6 -0.4372552934000001,51.5163857558,609.6 -0.4430962754,51.51760834980001,609.6 -0.4490934002,51.5184891791,609.6 -0.4551953742000001,51.5190207088,609.6 -0.46135,51.519198392,609.6 + + + + +
+ + EGRU128B LONDON HEATHROW RWY 09L + 512814N 0003325W -
512902N 0003325W -
512903N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512814N 0003137W -
512814N 0003325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5569003333,51.4704933333,609.6 -0.5270472778,51.4706154722,609.6 -0.5277391047,51.473972328,609.6 -0.5279918993,51.4773531895,609.6 -0.527803899,51.4807356961,609.6 -0.52717625,51.48409747220001,609.6 -0.5570173333,51.48397538890001,609.6 -0.5569003333,51.4704933333,609.6 + + + + +
+ + EGRU128C LONDON HEATHROW RWY 27R + 512905N 0002141W -
512816N 0002141W -
512816N 0002344W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512904N 0002344W -
512905N 0002141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3613735833,51.4846374722,609.6 -0.3956410556000001,51.4845450833,609.6 -0.3949547368,51.4811877781,609.6 -0.3947077047,51.4778067502,609.6 -0.3949014835999999,51.47442436730001,609.6 -0.3955346944,51.471063,609.6 -0.3612565833,51.47115541669999,609.6 -0.3613735833,51.4846374722,609.6 + + + + +
+ + EGRU128D LONDON HEATHROW RWY 09R + 512728N 0003315W -
512817N 0003316W -
512817N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512729N 0003112W -
512728N 0003315W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5542044167,51.45779225,609.6 -0.5200781389,51.4579273056,609.6 -0.5225554954,51.46113478249999,609.6 -0.5245850906,51.4644627941,609.6 -0.5261519863,51.4678869878,609.6 -0.5272446111,51.4713823056,609.6 -0.5543178889,51.47127436110001,609.6 -0.5542044167,51.45779225,609.6 + + + + +
+ + EGRU128E LONDON HEATHROW RWY 27L + 512819N 0002144W -
512730N 0002144W -
512730N 0002408W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512819N 0002343W -
512819N 0002144W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3622085,51.4719051944,609.6 -0.3953535278,51.4718188333,609.6 -0.3963867682,51.4683164757,609.6 -0.397895493,51.46488210049999,609.6 -0.3998685359,51.4615408393,609.6 -0.4022913611,51.4583171389,609.6 -0.3620950278,51.4584231111,609.6 -0.3622085,51.4719051944,609.6 + + + + +
+ + EGRU129A NORTHOLT + A circle, 2 NM radius, centred at 513310N 0002511W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4197222222,51.5860694194,609.6 -0.4252170924999999,51.58589284140001,609.6 -0.4306535891,51.5853649835,609.6 -0.4359739627,51.58449145300001,609.6 -0.4411217051,51.5832815289,609.6 -0.4460421536,51.5817480627,609.6 -0.4506830738000001,51.5799073411,609.6 -0.4549952171,51.5777789117,609.6 -0.4589328445,51.5753853748,609.6 -0.4624542133000001,51.5727521418,609.6 -0.4655220189,51.56990716420001,609.6 -0.4681037901,51.5668806359,609.6 -0.4701722306,51.5637046715,609.6 -0.4717055057,51.56041296439999,609.6 -0.4726874696,51.5570404286,609.6 -0.4731078322,51.5536228274,609.6 -0.4729622633,51.5501963944,609.6 -0.4722524326,51.5467974485,609.6 -0.4709859873,51.54346200929999,609.6 -0.4691764654,51.5402254156,609.6 -0.4668431476,51.53712195180001,609.6 -0.4640108489,51.53418448519999,609.6 -0.4607096516,51.5314441189,609.6 -0.4569745846,51.5289298638,609.6 -0.45284525,51.5266683326,609.6 -0.4483654033,51.5246834591,609.6 -0.4435824903,51.5229962465,609.6 -0.4385471456000001,51.521624546,609.6 -0.4333126589,51.5205828693,609.6 -0.4279344138,51.51988223559999,609.6 -0.4224693049,51.5195300562,609.6 -0.4169751395,51.5195300562,609.6 -0.4115100306,51.51988223559999,609.6 -0.4061317855,51.5205828693,609.6 -0.4008972988,51.521624546,609.6 -0.3958619541,51.5229962465,609.6 -0.3910790411,51.5246834591,609.6 -0.3865991945000001,51.5266683326,609.6 -0.3824698599,51.5289298638,609.6 -0.3787347928,51.5314441189,609.6 -0.3754335956,51.53418448519999,609.6 -0.3726012968,51.53712195180001,609.6 -0.3702679791,51.5402254156,609.6 -0.3684584571999999,51.54346200929999,609.6 -0.3671920117999999,51.5467974485,609.6 -0.3664821812,51.5501963944,609.6 -0.3663366122,51.5536228274,609.6 -0.3667569749,51.5570404286,609.6 -0.3677389388,51.56041296439999,609.6 -0.3692722138,51.5637046715,609.6 -0.3713406543,51.5668806359,609.6 -0.3739224255,51.56990716420001,609.6 -0.3769902312,51.5727521418,609.6 -0.3805115998999999,51.5753853748,609.6 -0.3844492274,51.5777789117,609.6 -0.3887613706,51.5799073411,609.6 -0.3934022908,51.5817480627,609.6 -0.3983227393,51.5832815289,609.6 -0.4034704818,51.58449145300001,609.6 -0.4087908553,51.5853649835,609.6 -0.414227352,51.58589284140001,609.6 -0.4197222222,51.5860694194,609.6 + + + + +
+ + EGRU129B NORTHOLT RWY 07 + 513150N 0002942W -
513221N 0003000W -
513244N 0002819W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513214N 0002801W -
513150N 0002942W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4949055556,51.5306527778,609.6 -0.466825,51.53710075,609.6 -0.4689011239999999,51.5398120238,609.6 -0.4705770388,51.54262895259999,609.6 -0.4718390278,51.5455286111,609.6 -0.4998722221999999,51.5390916667,609.6 -0.4949055556,51.5306527778,609.6 + + + + +
+ + EGRU129C NORTHOLT RWY 25 + 513430N 0002035W -
513400N 0002017W -
513335N 0002203W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513406N 0002221W -
513430N 0002035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3429888889,51.5750055556,609.6 -0.3724551111,51.5682804444,609.6 -0.3704066466,51.5655610198,609.6 -0.3687601003,51.5627375531,609.6 -0.3675288056,51.55983305560001,609.6 -0.3380138889,51.5665694444,609.6 -0.3429888889,51.5750055556,609.6 + + + + +
+ + EGRU130A LONDON LUTON + A circle, 2.5 NM radius, centred at 515229N 0002206W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3684444444,51.9162427857,609.6 -0.3746532062,51.91606511220001,609.6 -0.3808088511,51.91553361169999,609.6 -0.3868587204,51.9146528312,609.6 -0.3927510676,51.91343030509999,609.6 -0.3984355044,51.9118764909,609.6 -0.4038634347,51.9100046782,609.6 -0.4089884723,51.9078308751,609.6 -0.4137668395,51.9053736697,609.6 -0.4181577423,51.90265407,609.6 -0.4221237193999999,51.8996953238,609.6 -0.4256309617,51.89652271809999,609.6 -0.4286495997,51.8931633624,609.6 -0.4311539569,51.8896459557,609.6 -0.4331227659,51.8860005403,609.6 -0.4345393464,51.8822582448,609.6 -0.4353917437,51.8784510169,609.6 -0.4356728262,51.8746113507,609.6 -0.4353803413,51.870772009,609.6 -0.4345169299,51.8669657435,609.6 -0.4330900986,51.8632250155,609.6 -0.4311121514,51.8595817194,609.6 -0.4286000794,51.8560669116,609.6 -0.4255754131,51.8527105458,609.6 -0.4220640341,51.8495412194,609.6 -0.4180959529,51.8465859299,609.6 -0.41370505,51.84386984689999,609.6 -0.408928787,51.8414160983,609.6 -0.4038078861000001,51.8392455744,609.6 -0.3983859841,51.83737675170001,609.6 -0.3927092619,51.8358255363,609.6 -0.3868260530000001,51.8346051295,609.6 -0.3807864345,51.8337259165,609.6 -0.3746418038,51.8331953784,609.6 -0.3684444444,51.8330180294,609.6 -0.3622470850999999,51.8331953784,609.6 -0.3561024544,51.8337259165,609.6 -0.3500628358,51.8346051295,609.6 -0.344179627,51.8358255363,609.6 -0.3385029048,51.83737675170001,609.6 -0.3330810028,51.8392455744,609.6 -0.3279601019,51.8414160983,609.6 -0.3231838389,51.84386984689999,609.6 -0.318792936,51.8465859299,609.6 -0.3148248548,51.8495412194,609.6 -0.3113134758,51.8527105458,609.6 -0.3082888095,51.8560669116,609.6 -0.3057767375,51.8595817194,609.6 -0.3037987903,51.8632250155,609.6 -0.302371959,51.8669657435,609.6 -0.3015085476,51.870772009,609.6 -0.3012160627,51.8746113507,609.6 -0.3014971452,51.8784510169,609.6 -0.3023495425,51.8822582448,609.6 -0.303766123,51.8860005403,609.6 -0.3057349319,51.8896459557,609.6 -0.3082392892,51.8931633624,609.6 -0.3112579272,51.89652271809999,609.6 -0.3147651695,51.8996953238,609.6 -0.3187311466,51.90265407,609.6 -0.3231220494,51.9053736697,609.6 -0.3279004166,51.9078308751,609.6 -0.3330254542,51.9100046782,609.6 -0.3384533845,51.9118764909,609.6 -0.3441378213,51.91343030509999,609.6 -0.3500301685,51.9146528312,609.6 -0.3560800378,51.91553361169999,609.6 -0.3622356827,51.91606511220001,609.6 -0.3684444444,51.9162427857,609.6 + + + + +
+ + EGRU130B LONDON LUTON RWY 07 + 515120N 0002706W -
515151N 0002720W -
515204N 0002605W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to
515133N 0002551W -
515120N 0002706W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4515333333,51.8555694444,609.6 -0.4308439444000001,51.8591609444,609.6 -0.4324842643,51.8619845779,609.6 -0.4337918297000001,51.8648740476,609.6 -0.4347598055999999,51.8678143333,609.6 -0.4554361110999999,51.864225,609.6 -0.4515333333,51.8555694444,609.6 + + + + +
+ + EGRU130C LONDON LUTON RWY 25 + 515336N 0001711W -
515305N 0001657W -
515253N 0001808W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515229N 0002206W to
515324N 0001822W -
515336N 0001711W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2864888889,51.8934305556,609.6 -0.3060048333,51.8900711944,609.6 -0.3043708809,51.88724578839999,609.6 -0.3030704243,51.8843548473,609.6 -0.3021101667,51.8814134167,609.6 -0.2825805556,51.884775,609.6 -0.2864888889,51.8934305556,609.6 + + + + +
+ + EGRU131A ELSTREE + A circle, 2 NM radius, centred at 513921N 0001933W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.32585,51.68911605390001,609.6 -0.3313573375,51.68893947859999,609.6 -0.3368061684,51.68841162860001,609.6 -0.3421386119,51.6875381112,609.6 -0.3472980312,51.6863282054,609.6 -0.3522296393,51.68479476259999,609.6 -0.3568810829999999,51.6829540693,609.6 -0.3612030018,51.680825673,609.6 -0.365149553,51.6784321737,609.6 -0.3686788992,51.67579898259999,609.6 -0.3717536515000001,51.672954051,609.6 -0.3743412651,51.6699275723,609.6 -0.3764143825,51.66675166080001,609.6 -0.3779511197,51.66346000930001,609.6 -0.378935295,51.6600875314,609.6 -0.3793565956,51.6566699898,609.6 -0.3792106819,51.65324361759999,609.6 -0.3784992283,51.6498447329,609.6 -0.3772298997,51.6465093546,609.6 -0.3754162653999999,51.64327282090001,609.6 -0.3730776505000001,51.64016941549999,609.6 -0.3702389262,51.6372320048,609.6 -0.3669302437,51.6344916913,609.6 -0.3631867112000001,51.6319774852,609.6 -0.3590480206,51.62971599849999,609.6 -0.3545580267,51.62773116449999,609.6 -0.3497642823,51.62604398559999,609.6 -0.3447175366,51.6246723128,609.6 -0.3394711997,51.62363065710001,609.6 -0.3340807801,51.6229300376,609.6 -0.3286033007,51.62257786529999,609.6 -0.3230966993,51.62257786529999,609.6 -0.3176192199,51.6229300376,609.6 -0.3122288003,51.62363065710001,609.6 -0.3069824634,51.6246723128,609.6 -0.3019357177,51.62604398559999,609.6 -0.2971419733,51.62773116449999,609.6 -0.2926519794,51.62971599849999,609.6 -0.2885132888,51.6319774852,609.6 -0.2847697563,51.6344916913,609.6 -0.2814610738,51.6372320048,609.6 -0.2786223495,51.64016941549999,609.6 -0.2762837346,51.64327282090001,609.6 -0.2744701003,51.6465093546,609.6 -0.2732007717,51.6498447329,609.6 -0.2724893181,51.65324361759999,609.6 -0.2723434044,51.6566699898,609.6 -0.272764705,51.6600875314,609.6 -0.2737488803,51.66346000930001,609.6 -0.2752856175,51.66675166080001,609.6 -0.2773587349,51.6699275723,609.6 -0.2799463485,51.672954051,609.6 -0.2830211008,51.67579898259999,609.6 -0.286550447,51.6784321737,609.6 -0.2904969982,51.680825673,609.6 -0.294818917,51.6829540693,609.6 -0.2994703607,51.68479476259999,609.6 -0.3044019688,51.6863282054,609.6 -0.3095613881,51.6875381112,609.6 -0.3148938316,51.68841162860001,609.6 -0.3203426625,51.68893947859999,609.6 -0.32585,51.68911605390001,609.6 + + + + +
+ + EGRU131B ELSTREE RWY 08 + 513834N 0002401W -
513906N 0002410W -
513916N 0002246W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513844N 0002236W -
513834N 0002401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.40025,51.6427944444,609.6 -0.3767162778,51.6454770833,609.6 -0.3780102409,51.64837118879999,609.6 -0.3788797193999999,51.6513260665,609.6 -0.3793175556,51.6543176667,609.6 -0.4028416667,51.6516361111,609.6 -0.40025,51.6427944444,609.6 + + + + +
+ + EGRU131C ELSTREE RWY 26 + 514008N 0001505W -
513936N 0001456W -
513926N 0001621W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513958N 0001630W -
514008N 0001505W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.251425,51.66880833330001,609.6 -0.2749615278,51.6661527222,609.6 -0.2736733649,51.6632575555,609.6 -0.2728102231,51.6603019573,609.6 -0.2723790556,51.65731000000001,609.6 -0.2488333333,51.65996666670001,609.6 -0.251425,51.66880833330001,609.6 + + + + +
+ + EGRU132A LONDON GATWICK + A circle, 2.5 NM radius, centred at 510853N 0001125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1902777778,51.1896729688,609.6 -0.1963884086,51.1894952774,609.6 -0.2024467658,51.1889637232,609.6 -0.2084010264,51.1880828533,609.6 -0.214200265,51.1868602024,609.6 -0.2197948925,51.1853062283,609.6 -0.225137083,51.1834342212,609.6 -0.2301811851,51.1812601899,609.6 -0.2348841136,51.1788027231,609.6 -0.2392057194,51.1760828302,609.6 -0.2431091322,51.1731237601,609.6 -0.2465610756,51.1699508017,609.6 -0.2495321498,51.1665910662,609.6 -0.2519970809,51.16307325490001,609.6 -0.2539349337,51.15942741280001,609.6 -0.2553292873,51.1556846713,609.6 -0.2561683713,51.1518769815,609.6 -0.2564451617,51.1480368411,609.6 -0.2561574367,51.1441970168,609.6 -0.2553077906,51.1403902646,609.6 -0.2539036069,51.1366490502,609.6 -0.2519569908,51.1330052727,609.6 -0.2494846615,51.1294899933,609.6 -0.2465078063,51.1261331707,609.6 -0.243051896,51.1229634069,609.6 -0.2391464653,51.12000770460001,609.6 -0.2348248596,51.1172912377,609.6 -0.2301239488,51.11483713860001,609.6 -0.2250838137,51.1126663019,609.6 -0.2197474041,51.1107972077,609.6 -0.2141601747,51.10924576549999,609.6 -0.2083696995,51.1080251793,609.6 -0.202425269,51.10714583639999,609.6 -0.1963774741,51.1066152198,609.6 -0.1902777778,51.1064378445,609.6 -0.1841780815,51.1066152198,609.6 -0.1781302865,51.10714583639999,609.6 -0.1721858561,51.1080251793,609.6 -0.1663953808,51.10924576549999,609.6 -0.1608081514,51.1107972077,609.6 -0.1554717418,51.1126663019,609.6 -0.1504316067,51.11483713860001,609.6 -0.145730696,51.1172912377,609.6 -0.1414090902,51.12000770460001,609.6 -0.1375036596,51.1229634069,609.6 -0.1340477492,51.1261331707,609.6 -0.131070894,51.1294899933,609.6 -0.1285985648,51.1330052727,609.6 -0.1266519486,51.1366490502,609.6 -0.1252477649,51.1403902646,609.6 -0.1243981188,51.1441970168,609.6 -0.1241103939,51.1480368411,609.6 -0.1243871843,51.1518769815,609.6 -0.1252262682,51.1556846713,609.6 -0.1266206218,51.15942741280001,609.6 -0.1285584746,51.16307325490001,609.6 -0.1310234057,51.1665910662,609.6 -0.13399448,51.1699508017,609.6 -0.1374464234,51.1731237601,609.6 -0.1413498362,51.1760828302,609.6 -0.1456714419,51.1788027231,609.6 -0.1503743705,51.1812601899,609.6 -0.1554184725,51.1834342212,609.6 -0.1607606631,51.1853062283,609.6 -0.1663552906,51.1868602024,609.6 -0.1721545292,51.1880828533,609.6 -0.1781087898,51.1889637232,609.6 -0.1841671469,51.1894952774,609.6 -0.1902777778,51.1896729688,609.6 + + + + +
+ + EGRU132B LONDON GATWICK RWY 08L + 510801N 0001635W -
510832N 0001646W -
510844N 0001523W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510812N 0001514W -
510801N 0001635W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2763583333,51.13347222219999,609.6 -0.2538749722,51.1365861111,609.6 -0.2550266082,51.13950194939999,609.6 -0.255840969,51.1424624516,609.6 -0.25631375,51.1454521944,609.6 -0.2794138889,51.1422527778,609.6 -0.2763583333,51.13347222219999,609.6 + + + + +
+ + EGRU132C LONDON GATWICK RWY 26R + 510954N 0000652W -
510922N 0000641W -
510916N 0000730W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510947N 0000743W -
510954N 0000652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1143222222,51.1650083333,609.6 -0.1285487778,51.16305747220001,609.6 -0.126990203,51.1602170511,609.6 -0.1257617811,51.1573133081,609.6 -0.1248698611,51.15436138890001,609.6 -0.1112583333,51.15622777780001,609.6 -0.1143222222,51.1650083333,609.6 + + + + +
+ + EGRU132D LONDON GATWICK RWY 08R + 510755N 0001630W -
510826N 0001641W -
510837N 0001522W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510806N 0001511W -
510755N 0001630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2750777778,51.13181388890001,609.6 -0.2530278889,51.1348706667,609.6 -0.2543771033,51.1377494398,609.6 -0.2553931703,51.14068189130001,609.6 -0.25607075,51.1436527778,609.6 -0.2781333333,51.1405944444,609.6 -0.2750777778,51.13181388890001,609.6 + + + + +
+ + EGRU132E LONDON GATWICK RWY 26L + 510953N 0000613W -
510921N 0000602W -
510909N 0000728W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 510853N 0001125W to
510941N 0000739W -
510953N 0000613W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1036388889,51.1646583333,609.6 -0.1275807778,51.1613735,609.6 -0.1262195947,51.15849728829999,609.6 -0.1251916959,51.1555668638,609.6 -0.1245023611,51.1525974722,609.6 -0.100575,51.1558805556,609.6 -0.1036388889,51.1646583333,609.6 + + + + +
+ + EGRU133A REDHILL + 511134N 0001048W thence clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511230N 0000511W -
511134N 0001048W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.18,51.1927777778,609.6 -0.0863888889,51.2083333333,609.6 -0.08577830810000001,51.2117007276,609.6 -0.0857454411,51.2150907095,609.6 -0.0862619904,51.2184651944,609.6 -0.0873227125,51.2217891473,609.6 -0.08891670810000001,51.2250280504,609.6 -0.09102753099999999,51.2281482618,609.6 -0.0936333542,51.231117366,609.6 -0.09670719309999999,51.23390451120001,609.6 -0.1002171832,51.2364807312,609.6 -0.1041269087,51.2388192469,609.6 -0.1083957801,51.24089574650001,609.6 -0.1129794553,51.242688639,609.6 -0.1178303017,51.24417928,609.6 -0.1228978922,51.2453521666,609.6 -0.1281295323,51.2461950995,609.6 -0.1334708104,51.2466993108,609.6 -0.1388661674,51.2468595556,609.6 -0.144259478,51.24667416699999,609.6 -0.1495946383,51.24614507329999,609.6 -0.1548161531,51.2452777785,609.6 -0.1598697169,51.2440813036,609.6 -0.1647027819,51.24256809340001,609.6 -0.1692651072,51.2407538854,609.6 -0.1735092831,51.2386575454,609.6 -0.1773912259,51.2363008705,609.6 -0.1808706361,51.23370836099999,609.6 -0.1839114173,51.230906965,609.6 -0.1864820495,51.2279257965,609.6 -0.1885559151,51.22479583219999,609.6 -0.1901115721,51.2215495885,609.6 -0.1911329731,51.2182207829,609.6 -0.1916096276,51.2148439831,609.6 -0.1915367066,51.21145424760001,609.6 -0.1909150876,51.20808676159999,609.6 -0.1897513404,51.20477647189999,609.6 -0.1880576543,51.2015577241,609.6 -0.1858517068,51.1984639072,609.6 -0.1831564762,51.1955271077,609.6 -0.18,51.1927777778,609.6 + + + + +
+ + EGRU133B REDHILL RWY 07L + 511150N 0001237W -
511221N 0001251W -
511235N 0001129W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511204N 0001116W -
511150N 0001237W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2102416667,51.1971527778,609.6 -0.1877980556,51.2010925556,609.6 -0.1893926122,51.2039255796,609.6 -0.1905742304,51.2068373717,609.6 -0.1913332222,51.20980422220001,609.6 -0.2140805556,51.2058111111,609.6 -0.2102416667,51.1971527778,609.6 + + + + +
+ + EGRU133C REDHILL RWY 25R + 511354N 0000400W -
511323N 0000347W -
511308N 0000511W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511339N 0000526W -
511354N 0000400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.06679722220000001,51.231575,609.6 -0.0904669444,51.22744897220001,609.6 -0.08867417470000001,51.2246628442,609.6 -0.0872889642,51.2217865477,609.6 -0.08632252780000001,51.2188435278,609.6 -0.0629555556,51.2229166667,609.6 -0.06679722220000001,51.231575,609.6 + + + + +
+ + EGRU133D REDHILL RWY 07R + 511146N 0001243W -
511218N 0001257W -
511233N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511202N 0001115W -
511146N 0001243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2119305556,51.19623611109999,609.6 -0.1873991111,51.2004910278,609.6 -0.18908136,51.2033034861,609.6 -0.1903533425,51.2061997519,609.6 -0.1912046389,51.20915625,609.6 -0.2157277778,51.2049027778,609.6 -0.2119305556,51.19623611109999,609.6 + + + + +
+ + EGRU133E REDHILL RWY 25L + 511351N 0000355W -
511320N 0000342W -
511305N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511336N 0000524W -
511351N 0000355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0653694444,51.23088888889999,609.6 -0.0899130833,51.22666225,609.6 -0.08823586479999999,51.2238484928,609.6 -0.0869696108,51.2209512348,609.6 -0.0861245556,51.2179940833,609.6 -0.0615722222,51.2222222222,609.6 -0.0653694444,51.23088888889999,609.6 + + + + +
+ + EGRU133F REDHILL RWY 18 + 511545N 0000848W -
511545N 0000756W -
511448N 0000758W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511447N 0000849W -
511545N 0000848W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1465555556,51.2626111111,609.6 -0.1470106389,51.24646522220001,609.6 -0.1422509249,51.2468036602,609.6 -0.1374619454,51.2468710493,609.6 -0.1326828333,51.2466668333,609.6 -0.1322333333,51.2624527778,609.6 -0.1465555556,51.2626111111,609.6 + + + + +
+ + EGRU133G REDHILL RWY 36 + 510959N 0000806W -
510959N 0000857W -
511153N 0000854W -
511202N 0000802W -
510959N 0000806W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1349666667,51.1662944444,609.6 -0.1339975833,51.2004327778,609.6 -0.1483735833,51.19804275,609.6 -0.1492611111,51.1664555556,609.6 -0.1349666667,51.1662944444,609.6 + + + + +
+ + EGRU133H REDHILL RWY H07 + 511147N 0001226W -
511218N 0001240W -
511230N 0001128W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511159N 0001113W -
511147N 0001226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2073083333,51.19628888889999,609.6 -0.1869276111,51.19981977780001,609.6 -0.1887082862,51.2026087033,609.6 -0.1900816288,51.2054871169,609.6 -0.1910363889,51.2084315833,609.6 -0.2111,51.2049555556,609.6 -0.2073083333,51.19628888889999,609.6 + + + + +
+ + EGRU133I REDHILL RWY H25 + 511345N 0000415W -
511314N 0000401W -
511302N 0000510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511333N 0000522W -
511345N 0000415W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.07071388889999999,51.2291944444,609.6 -0.08945697219999998,51.2259695,609.6 -0.0878808339,51.22313219359999,609.6 -0.0867187109,51.22021718879999,609.6 -0.0859799722,51.21724825,609.6 -0.0669194444,51.2205277778,609.6 -0.07071388889999999,51.2291944444,609.6 + + + + +
+ + EGRU133J REDHILL RWY H18 + 511528N 0000927W -
511530N 0000836W -
511449N 0000832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 511249N 0000819W to
511442N 0000923W -
511528N 0000927W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.157575,51.2578166667,609.6 -0.1562663333,51.2449930556,609.6 -0.1516398746,51.24586868730001,609.6 -0.146905405,51.24647597479999,609.6 -0.1421024444,51.24681013890001,609.6 -0.1432805556,51.2583888889,609.6 -0.157575,51.2578166667,609.6 + + + + +
+ + EGRU133K REDHILL RWY H36 + 511002N 0000802W -
511000N 0000854W -
511151N 0000905W -
511200N 0000814W -
511002N 0000802W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1340222222,51.1672388889,609.6 -0.1373332778,51.1998783889,609.6 -0.1514294722,51.1975344444,609.6 -0.1482888889,51.1666666667,609.6 -0.1340222222,51.1672388889,609.6 + + + + +
+ + EGRU134A BIGGIN HILL + A circle, 2.5 NM radius, centred at 511951N 0000157E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0325,51.37244943980001,609.6 0.02636507,51.372271753,609.6 0.0202826224,51.3717402124,609.6 0.0143046872,51.37085936500001,609.6 0.008482393,51.36963674569999,609.6 0.0028655268,51.368082812,609.6 -0.0024978947,51.3662108541,609.6 -0.0075620381,51.3640368805,609.6 -0.012283647,51.3615794797,609.6 -0.0166224123,51.3588596609,609.6 -0.0205413175,51.3559006727,609.6 -0.0240069543,51.35272780330001,609.6 -0.0269898066,51.34936816370001,609.6 -0.0294645007,51.3458504545,609.6 -0.0314100192,51.3422047201,609.6 -0.0328098769,51.3384620911,609.6 -0.0336522578,51.3346545178,609.6 -0.0339301114,51.330814497,609.6 -0.033641208,51.32697479440001,609.6 -0.0327881536,51.3231681648,609.6 -0.0313783621,51.3194270729,609.6 -0.0294239879,51.31578341669999,609.6 -0.0269418177,51.3122682561,609.6 -0.0239531235,51.3089115485,609.6 -0.0204834779,51.3057418948,609.6 -0.0165625336,51.3027862964,609.6 -0.0122237683,51.3000699262,609.6 -0.0075041985,51.2976159153,609.6 -0.0024440638,51.2954451573,609.6 0.0029135158,51.29357613139999,609.6 0.008522905900000001,51.2920247463,609.6 0.0143363443,51.29080420519999,609.6 0.0203043458,51.289924895,609.6 0.0263761198,51.2893942982,609.6 0.0325,51.2892169295,609.6 0.0386238802,51.2893942982,609.6 0.0446956542,51.289924895,609.6 0.0506636557,51.29080420519999,609.6 0.0564770941,51.2920247463,609.6 0.0620864842,51.29357613139999,609.6 0.0674440638,51.2954451573,609.6 0.07250419850000001,51.2976159153,609.6 0.0772237683,51.3000699262,609.6 0.0815625336,51.3027862964,609.6 0.08548347789999999,51.3057418948,609.6 0.08895312349999998,51.3089115485,609.6 0.09194181770000001,51.3122682561,609.6 0.09442398790000001,51.31578341669999,609.6 0.0963783621,51.3194270729,609.6 0.09778815359999998,51.3231681648,609.6 0.09864120799999999,51.32697479440001,609.6 0.09893011139999999,51.330814497,609.6 0.0986522578,51.3346545178,609.6 0.0978098769,51.3384620911,609.6 0.0964100192,51.3422047201,609.6 0.0944645007,51.3458504545,609.6 0.09198980660000002,51.34936816370001,609.6 0.0890069543,51.35272780330001,609.6 0.08554131750000001,51.3559006727,609.6 0.0816224123,51.3588596609,609.6 0.077283647,51.3615794797,609.6 0.0725620381,51.3640368805,609.6 0.06749789470000001,51.3662108541,609.6 0.06213447319999999,51.368082812,609.6 0.056517607,51.36963674569999,609.6 0.0506953128,51.37085936500001,609.6 0.0447173776,51.3717402124,609.6 0.03863493,51.372271753,609.6 0.0325,51.37244943980001,609.6 + + + + +
+ + EGRU134B BIGGIN HILL RWY 03 + 511700N 0000013E -
511714N 0000033W -
511744N 0000010W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to
511730N 0000037E -
511700N 0000013E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0037444444,51.28320277779999,609.6 0.0102089167,51.2916319722,609.6 0.0057608933,51.2927401761,609.6 0.0014515666,51.2940463129,609.6 -0.0026966944,51.29554361109999,609.6 -0.009169444400000001,51.2871,609.6 0.0037444444,51.28320277779999,609.6 + + + + +
+ + EGRU134C BIGGIN HILL RWY 21 + 512251N 0000346E -
512236N 0000432E -
512158N 0000403E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 511951N 0000157E to
512212N 0000316E -
512251N 0000346E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0627277778,51.38069444439999,609.6 0.0545643611,51.3700889167,609.6 0.05902709,51.368990418,609.6 0.0633514721,51.3676932629,609.6 0.0675149722,51.3662042222,609.6 0.0756722222,51.3767972222,609.6 0.0627277778,51.38069444439999,609.6 + + + + +
+ + EGRU135A LONDON CITY + A circle, 2 NM radius, centred at 513019N 0000319E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0551777778,51.5385224685,609.6 0.049688635,51.5383458893,609.6 0.04425780480000001,51.5378180277,609.6 0.0389429762,51.5369444912,609.6 0.0338005981,51.53573455860001,609.6 0.0288852764,51.5342010816,609.6 0.0242491907,51.5323603469,609.6 0.0199415384,51.53023190230001,609.6 0.0160080105,51.527838348,609.6 0.0124903067,51.5252050956,609.6 0.0094256923,51.5223600968,609.6 0.0068466052,51.5193335456,609.6 0.0047803132,51.5161575568,609.6 0.0032486287,51.512865824,609.6 0.0022676808,51.5094932614,609.6 0.001847749,51.5060756327,609.6 0.0019931596,51.50264917169999,609.6 0.0027022447,51.4992501975,609.6 0.0039673655,51.4959147301,609.6 0.005774998199999999,51.49267810879999,609.6 0.0081058824,51.489574618,609.6 0.0109352292,51.48663712559999,609.6 0.0142329877,51.4838967349,609.6 0.0179641657,51.4813824572,609.6 0.0220892021,51.4791209055,609.6 0.0265643871,51.4771360138,609.6 0.0313423241,51.47544878560001,609.6 0.0363724312,51.4740770724,609.6 0.0416014737,51.473035386,609.6 0.0469741258,51.4723347457,609.6 0.05243355169999999,51.471982563,609.6 0.0579220039,51.471982563,609.6 0.0633814298,51.4723347457,609.6 0.06875408180000001,51.473035386,609.6 0.0739831244,51.4740770724,609.6 0.07901323139999999,51.47544878560001,609.6 0.0837911685,51.4771360138,609.6 0.0882663534,51.4791209055,609.6 0.0923913899,51.4813824572,609.6 0.0961225678,51.4838967349,609.6 0.0994203263,51.48663712559999,609.6 0.1022496732,51.489574618,609.6 0.1045805574,51.49267810879999,609.6 0.1063881901,51.4959147301,609.6 0.1076533108,51.4992501975,609.6 0.1083623959,51.50264917169999,609.6 0.1085078065,51.5060756327,609.6 0.1080878748,51.5094932614,609.6 0.1071069268,51.512865824,609.6 0.1055752423,51.5161575568,609.6 0.1035089504,51.5193335456,609.6 0.1009298632,51.5223600968,609.6 0.09786524889999999,51.5252050956,609.6 0.094347545,51.527838348,609.6 0.0904140172,51.53023190230001,609.6 0.0861063648,51.5323603469,609.6 0.0814702792,51.5342010816,609.6 0.0765549574,51.53573455860001,609.6 0.0714125794,51.5369444912,609.6 0.06609775079999999,51.5378180277,609.6 0.06066692059999999,51.5383458893,609.6 0.0551777778,51.5385224685,609.6 + + + + +
+ + EGRU135B LONDON CITY RWY 09 + 513012N 0000136W -
513044N 0000133W -
513041N 0000010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513009N 0000007E -
513012N 0000136W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0265288333,51.50327555559999,609.6 0.0020265,51.5023953889,609.6 0.0018316307,51.50539711759999,609.6 0.0020711489,51.5083975865,609.6 0.0027431944,51.5113723611,609.6 -0.0258050833,51.5122523333,609.6 -0.0265288333,51.50327555559999,609.6 + + + + +
+ + EGRU135C LONDON CITY RWY 27 + 513026N 0000814E -
512953N 0000811E -
512957N 0000627E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513029N 0000630E -
513026N 0000814E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1372346667,51.5071330556,609.6 0.1083335278,51.5080571389,609.6 0.1085236627,51.5050552868,609.6 0.1082794163,51.5020549588,609.6 0.1076028611,51.4990805833,609.6 0.136511,51.49815627780001,609.6 0.1372346667,51.5071330556,609.6 + + + + +
+ + EGRU136A STAPLEFORD + A circle, 2 NM radius, centred at 513909N 0000922E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1560083333,51.6857966284,609.6 0.1505013986,51.685620053,609.6 0.1450529662,51.68509220280001,609.6 0.1397209126,51.684218685,609.6 0.1345618705,51.68300877859999,609.6 0.129630623,51.681475335,609.6 0.1249795192,51.6796346408,609.6 0.1206579162,51.67750624340001,609.6 0.1167116533,51.6751127429,609.6 0.1131825649,51.67247955050001,609.6 0.110108037,51.6696346173,609.6 0.1075206121,51.66660813710001,609.6 0.1054476458,51.66343222390001,609.6 0.1039110205,51.6601405706,609.6 0.1029269166,51.6567680908,609.6 0.1025056463,51.6533505473,609.6 0.1026515488,51.6499241731,609.6 0.1033629501,51.6465252864,609.6 0.1046321855,51.6431899062,609.6 0.1064456869,51.6399533706,609.6 0.1087841307,51.6368499633,609.6 0.1116226474,51.63391255079999,609.6 0.1149310881,51.6311722356,609.6 0.1186743472,51.6286580279,609.6 0.1228127354,51.6263965398,609.6 0.1273024016,51.62441170450001,609.6 0.132095796,51.6227245245,609.6 0.1371421734,51.6213528508,609.6 0.1423881274,51.6203111944,609.6 0.1477781538,51.61961057449999,609.6 0.1532552335,51.61925840200001,609.6 0.1587614331,51.61925840200001,609.6 0.1642385129,51.61961057449999,609.6 0.1696285392,51.6203111944,609.6 0.1748744933,51.6213528508,609.6 0.1799208706,51.6227245245,609.6 0.1847142651,51.62441170450001,609.6 0.1892039312,51.6263965398,609.6 0.1933423195,51.6286580279,609.6 0.1970855786,51.6311722356,609.6 0.2003940193,51.63391255079999,609.6 0.2032325359,51.6368499633,609.6 0.2055709798,51.6399533706,609.6 0.2073844812,51.6431899062,609.6 0.2086537166,51.6465252864,609.6 0.2093651178,51.6499241731,609.6 0.2095110204,51.6533505473,609.6 0.2090897501,51.6567680908,609.6 0.2081056462,51.6601405706,609.6 0.2065690208,51.66343222390001,609.6 0.2044960546,51.66660813710001,609.6 0.2019086297,51.6696346173,609.6 0.1988341018,51.67247955050001,609.6 0.1953050134,51.6751127429,609.6 0.1913587504,51.67750624340001,609.6 0.1870371475,51.6796346408,609.6 0.1823860437,51.681475335,609.6 0.1774547962,51.68300877859999,609.6 0.172295754,51.684218685,609.6 0.1669637005,51.68509220280001,609.6 0.161515268,51.685620053,609.6 0.1560083333,51.6857966284,609.6 + + + + +
+ + EGRU136B STAPLEFORD RWY 03L + 513634N 0000654E -
513653N 0000612E -
513743N 0000708E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513724N 0000750E -
513634N 0000654E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.114975,51.6095305556,609.6 0.1306218889,51.62320063889999,609.6 0.1264803317,51.6247434871,609.6 0.1225788083,51.62651232070001,609.6 0.1189490556,51.62849275,609.6 0.1032222222,51.61475,609.6 0.114975,51.6095305556,609.6 + + + + +
+ + EGRU136C STAPLEFORD RWY 21R + 514140N 0001141E -
514122N 0001223E -
514037N 0001132E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514056N 0001050E -
514140N 0001141E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1946944444,51.6945361111,609.6 0.1804416944,51.6821273889,609.6 0.1846372067,51.6806366835,609.6 0.1885991606,51.6789167892,609.6 0.1922952778,51.67698175,609.6 0.2064694444,51.6893194444,609.6 0.1946944444,51.6945361111,609.6 + + + + +
+ + EGRU136D STAPLEFORD RWY 03R + 513634N 0000656E -
513652N 0000613E -
513742N 0000710E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513723N 0000752E -
513634N 0000656E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1154222222,51.6093166667,609.6 0.1311190278,51.62303599999999,609.6 0.126951311,51.6245517675,609.6 0.1230198351,51.6262951166,609.6 0.1193565833,51.6282518611,609.6 0.1036666667,51.61453611109999,609.6 0.1154222222,51.6093166667,609.6 + + + + +
+ + EGRU136E STAPLEFORD RWY 21L + 514140N 0001143E -
514121N 0001225E -
514036N 0001134E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514055N 0001051E -
514140N 0001143E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1951388889,51.6943527778,609.6 0.1809234167,51.68197180559999,609.6 0.1850942614,51.6804547511,609.6 0.1890278444,51.678710016,609.6 0.1926921111,51.67675183330001,609.6 0.2069138889,51.6891361111,609.6 0.1951388889,51.6943527778,609.6 + + + + +
+ + EGRU137A LONDON STANSTED + A circle, 2.5 NM radius, centred at 515306N 0001406E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.235,51.9266121564,609.6 0.2287898076,51.92643448310001,609.6 0.2226327443,51.92590298339999,609.6 0.2165814812,51.9250222041,609.6 0.2106877765,51.9237996799,609.6 0.2050020304,51.9222458679,609.6 0.1995728501,51.92037405800001,609.6 0.1944466326,51.9182002582,609.6 0.1896671656,51.9157430564,609.6 0.1852752525,51.9130234609,609.6 0.1813083633,51.9100647192,609.6 0.1778003149,51.90689211849999,609.6 0.1747809834,51.9035327683,609.6 0.1722760514,51.9000153673,609.6 0.1703067912,51.896369958,609.6 0.1688898867,51.8926276688,609.6 0.1680372953,51.8888204475,609.6 0.1677561503,51.8849807881,609.6 0.1680487046,51.8811414532,609.6 0.1689123167,51.87733519460001,609.6 0.1703394781,51.8735944735,609.6 0.1723178822,51.8699511843,609.6 0.1748305335,51.8664363832,609.6 0.1778558969,51.86308002400001,609.6 0.1813680845,51.8599107037,609.6 0.1853370792,51.85695542020001,609.6 0.1897289923,51.8542393427,609.6 0.1945063538,51.851785599,609.6 0.1996284322,51.8496150796,609.6 0.2050515805,51.84774626079999,609.6 0.2107296074,51.84619504860001,609.6 0.2166141682,51.8449746444,609.6 0.2226551744,51.8440954332,609.6 0.2288012169,51.8435648963,609.6 0.235,51.8433875477,609.6 0.2411987831,51.8435648963,609.6 0.2473448256,51.8440954332,609.6 0.2533858318,51.8449746444,609.6 0.2592703926,51.84619504860001,609.6 0.2649484195,51.84774626079999,609.6 0.2703715678,51.8496150796,609.6 0.2754936462,51.851785599,609.6 0.2802710077,51.8542393427,609.6 0.2846629208,51.85695542020001,609.6 0.2886319155,51.8599107037,609.6 0.2921441031,51.86308002400001,609.6 0.2951694665,51.8664363832,609.6 0.2976821178,51.8699511843,609.6 0.2996605219,51.8735944735,609.6 0.3010876833,51.87733519460001,609.6 0.3019512954,51.8811414532,609.6 0.3022438497,51.8849807881,609.6 0.3019627047,51.8888204475,609.6 0.3011101133,51.8926276688,609.6 0.2996932088,51.896369958,609.6 0.2977239486,51.9000153673,609.6 0.2952190166,51.9035327683,609.6 0.2921996851,51.90689211849999,609.6 0.2886916367,51.9100647192,609.6 0.2847247475,51.9130234609,609.6 0.2803328344,51.9157430564,609.6 0.2755533674,51.9182002582,609.6 0.2704271499,51.92037405800001,609.6 0.2649979696,51.9222458679,609.6 0.2593122235,51.9237996799,609.6 0.2534185188,51.9250222041,609.6 0.2473672557,51.92590298339999,609.6 0.2412101924,51.92643448310001,609.6 0.235,51.9266121564,609.6 + + + + +
+ + EGRU137B LONDON STANSTED RWY 04 + 515028N 0001044E -
515050N 0001005E -
515128N 0001103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515106N 0001141E -
515028N 0001044E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1788194444,51.8410361111,609.6 0.1947456944,51.85167430559999,609.6 0.1909710506,51.8535562167,609.6 0.187424914,51.8556015888,609.6 0.1841257222,51.85779980560001,609.6 0.1681888889,51.84715277780001,609.6 0.1788194444,51.8410361111,609.6 + + + + +
+ + EGRU137C LONDON STANSTED RWY 22 + 515552N 0001739E -
515530N 0001817E -
515444N 0001709E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515506N 0001630E -
515552N 0001739E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2941833333,51.93113055560001,609.6 0.2750736667,51.9184224444,609.6 0.2788639154,51.916548197,609.6 0.2824255347,51.9145097839,609.6 0.28574,51.91231783329999,609.6 0.3048388889,51.9250166667,609.6 0.2941833333,51.93113055560001,609.6 + + + + +
+ + EGRU138A ANDREWSFIELD + A circle, 2 NM radius, centred at 515342N 0002657E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4491666667,51.9282896919,609.6 0.4436301033,51.9281131227,609.6 0.4381523581,51.927585291,609.6 0.4327916200999999,51.926711804,609.6 0.4276048275,51.9255019406,609.6 0.422647059,51.9239685519,609.6 0.4179709460000001,51.92212792399999,609.6 0.4136261113,51.9199996043,609.6 0.4096586409,51.91760619210001,609.6 0.4061105941,51.9149730981,609.6 0.4030195576,51.9121282729,609.6 0.4004182481,51.90910190909999,609.6 0.3983341674,51.90592612,609.6 0.3967893144,51.9026345974,609.6 0.3957999552,51.8992622536,609.6 0.3953764561,51.89584485030001,609.6 0.3955231779999999,51.8924186188,609.6 0.3962384364,51.88901987600001,609.6 0.3975145241,51.88568463899999,609.6 0.3993377987,51.8824482445,609.6 0.4016888316,51.8793449744,609.6 0.4045426185,51.8764076934,609.6 0.4078688481,51.8736675024,609.6 0.4116322255,51.87115341000001,609.6 0.4157928483000001,51.86889202660001,609.6 0.4203066295,51.86690728399999,609.6 0.4251257647,51.86522018340001,609.6 0.4301992364,51.86384857459999,609.6 0.4354733526,51.86280696779999,609.6 0.4408923116999999,51.8621063813,609.6 0.4463987897999999,51.8617542257,609.6 0.4519345435,51.8617542257,609.6 0.4574410216,51.8621063813,609.6 0.4628599807,51.86280696779999,609.6 0.4681340969,51.86384857459999,609.6 0.4732075687,51.86522018340001,609.6 0.4780267038,51.86690728399999,609.6 0.4825404851000001,51.86889202660001,609.6 0.4867011077999999,51.87115341000001,609.6 0.4904644852,51.8736675024,609.6 0.4937907147999999,51.8764076934,609.6 0.4966445018,51.8793449744,609.6 0.4989955347,51.8824482445,609.6 0.5008188092,51.88568463899999,609.6 0.502094897,51.88901987600001,609.6 0.5028101553,51.8924186188,609.6 0.5029568773,51.89584485030001,609.6 0.5025333781,51.8992622536,609.6 0.5015440189,51.9026345974,609.6 0.4999991659,51.90592612,609.6 0.4979150853,51.90910190909999,609.6 0.4953137757,51.9121282729,609.6 0.4922227392,51.9149730981,609.6 0.4886746924,51.91760619210001,609.6 0.484707222,51.9199996043,609.6 0.4803623874,51.92212792399999,609.6 0.4756862743,51.9239685519,609.6 0.4707285057999999,51.9255019406,609.6 0.4655417132,51.926711804,609.6 0.4601809752,51.927585291,609.6 0.45470323,51.9281131227,609.6 0.4491666667,51.9282896919,609.6 + + + + +
+ + EGRU138B ANDREWSFIELD RWY 09L + 515311N 0002223E -
515343N 0002219E -
515348N 0002344E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515316N 0002348E -
515311N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3730888889,51.8864027778,609.6 0.3966865556,51.88766425,609.6 0.3958296993000001,51.89062131390001,609.6 0.3954070986,51.89361413149999,609.6 0.3954222778,51.8966183333,609.6 0.3718527778,51.8953583333,609.6 0.3730888889,51.8864027778,609.6 + + + + +
+ + EGRU138C ANDREWSFIELD RWY 27R + 515413N 0003137E -
515341N 0003142E -
515336N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515408N 0003006E -
515413N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5269916667,51.9035638889,609.6 0.5016900556,51.9022398056,609.6 0.5025295237,51.89928078159999,609.6 0.502934256,51.89628698540001,609.6 0.5029010556,51.8932828056,609.6 0.5282305556,51.89460833329999,609.6 0.5269916667,51.9035638889,609.6 + + + + +
+ + EGRU138D ANDREWSFIELD RWY 09R + 515310N 0002223E -
515342N 0002218E -
515347N 0002343E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515315N 0002348E -
515310N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3729722222,51.8861333333,609.6 0.3967850555999999,51.8873999167,609.6 0.3958892902,51.8903525916,609.6 0.3954272954,51.89334320879999,609.6 0.3954029167000001,51.8963474167,609.6 0.3717416667,51.8950888889,609.6 0.3729722222,51.8861333333,609.6 + + + + +
+ + EGRU138E ANDREWSFIELD RWY 27L + 515412N 0003137E -
515340N 0003142E -
515335N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515407N 0003006E -
515412N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5270416667,51.9032611111,609.6 0.50179325,51.90194663890001,609.6 0.502589532,51.8989830515,609.6 0.5029506279,51.8959871214,609.6 0.5028736667,51.89298324999999,609.6 0.5282722222,51.8943055556,609.6 0.5270416667,51.9032611111,609.6 + + + + +
+ + EGRU139A ROCHESTER + A circle, 2 NM radius, centred at 512107N 0003010E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5028888889000001,51.38515667770001,609.6 0.4974181135,51.3849800946,609.6 0.4920054548,51.3844522212,609.6 0.4867084083,51.38357866499999,609.6 0.4815832334,51.38236870509999,609.6 0.4766843526000001,51.3808351933,609.6 0.4720637707999999,51.3789944163,609.6 0.4677705203,51.3768659223,609.6 0.4638501395999999,51.3744723119,609.6 0.4603441886,51.3718389969,609.6 0.4572898085000001,51.3689939296,609.6 0.4547193289,51.3659673044,609.6 0.4526599272,51.3627912369,609.6 0.4511333435,51.3594994211,609.6 0.4501556536,51.3561267721,609.6 0.4497371038,51.3527090546,609.6 0.4498820067,51.349282503,609.6 0.4505887009,51.3458834377,609.6 0.4518495739000001,51.3425478795,609.6 0.4536511481,51.3393111687,609.6 0.4559742281999999,51.336207591,609.6 0.4587941085999999,51.3332700152,609.6 0.4620808394,51.3305295459,609.6 0.4657995454,51.3280151953,609.6 0.4699107981,51.3257535772,609.6 0.4743710333,51.32376862689999,609.6 0.4791330128999999,51.3220813485,609.6 0.4841463232,51.3207095942,609.6 0.4893579071999999,51.3196678763,609.6 0.4947126227999999,51.3189672149,609.6 0.5001538236,51.3186150215,609.6 0.5056239541999999,51.3186150215,609.6 0.511065155,51.3189672149,609.6 0.5164198706000001,51.3196678763,609.6 0.5216314546,51.3207095942,609.6 0.5266447649,51.3220813485,609.6 0.5314067444,51.32376862689999,609.6 0.5358669797,51.3257535772,609.6 0.5399782323,51.3280151953,609.6 0.5436969384,51.3305295459,609.6 0.5469836691,51.3332700152,609.6 0.5498035496,51.336207591,609.6 0.5521266296,51.3393111687,609.6 0.5539282038,51.3425478795,609.6 0.5551890769,51.3458834377,609.6 0.5558957711,51.349282503,609.6 0.5560406739,51.3527090546,609.6 0.5556221241,51.3561267721,609.6 0.5546444343,51.3594994211,609.6 0.5531178505,51.3627912369,609.6 0.5510584489,51.3659673044,609.6 0.5484879693,51.3689939296,609.6 0.5454335892,51.3718389969,609.6 0.5419276382,51.3744723119,609.6 0.5380072574,51.3768659223,609.6 0.533714007,51.3789944163,609.6 0.5290934252,51.3808351933,609.6 0.5241945444,51.38236870509999,609.6 0.5190693695,51.38357866499999,609.6 0.5137723229,51.3844522212,609.6 0.5083596643,51.3849800946,609.6 0.5028888889000001,51.38515667770001,609.6 + + + + +
+ + EGRU139B ROCHESTER RWY 02L + 511821N 0002901E -
511833N 0002812E -
511920N 0002842E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
511909N 0002931E -
511821N 0002901E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4834861111,51.3058194444,609.6 0.4918709444,51.3192941389,609.6 0.4872282527,51.320048953,609.6 0.4827129256000001,51.321062879,609.6 0.4783616944,51.32232766670001,609.6 0.4701277777999999,51.30908888889999,609.6 0.4834861111,51.3058194444,609.6 + + + + +
+ + EGRU139C ROCHESTER RWY 20R + 512359N 0003136E -
512347N 0003224E -
512250N 0003148E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
512302N 0003100E -
512359N 0003136E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5266194444,51.3997527778,609.6 0.51678675,51.38399999999999,609.6 0.5213616864,51.3830840819,609.6 0.5257857540999999,51.381913545,609.6 0.5300228333,51.38049794440001,609.6 0.5400055556,51.3964833333,609.6 0.5266194444,51.3997527778,609.6 + + + + +
+ + EGRU139D ROCHESTER RWY 02R + 511819N 0002902E -
511831N 0002814E -
511920N 0002844E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
511909N 0002933E -
511819N 0002902E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4839722222,51.3053888889,609.6 0.4924984444,51.3192133056,609.6 0.4878400458,51.31993329260001,609.6 0.4833041184,51.3209135101,609.6 0.4789275833000001,51.3221459722,609.6 0.4705972222,51.3086333333,609.6 0.4839722222,51.3053888889,609.6 + + + + +
+ + EGRU139E ROCHESTER RWY 20L + 512354N 0003134E -
512342N 0003222E -
512249N 0003149E thence anti-clockwise by the arc of a circle radius 2 NM centred on 512107N 0003010E to
512302N 0003102E -
512354N 0003134E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5259916667,51.3983277778,609.6 0.5170946389,51.3839471944,609.6 0.5216613468,51.38301395450001,609.6 0.5260746936,51.381826592,609.6 0.5302986389,51.38039480560001,609.6 0.5393916667,51.3950861111,609.6 0.5259916667,51.3983277778,609.6 + + + + +
+ + EGRU140A LASHENDEN/HEADCORN + A circle, 2 NM radius, centred at 510923N 0003840E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6444444444,51.1896827956,609.6 0.6389968451,51.1895062075,609.6 0.6336071153,51.188978319,609.6 0.6283325063,51.1881047377,609.6 0.6232290383,51.1868947429,609.6 0.6183509028,51.1853611865,609.6 0.6137498838,51.1835203555,609.6 0.6094748059,51.1813917985,609.6 0.6055710142,51.17899811629999,609.6 0.6020798931,51.17636472139999,609.6 0.5990384267,51.1735195665,609.6 0.5964788084,51.1704928469,609.6 0.5944281011,51.1673166787,609.6 0.5929079536,51.16402475700001,609.6 0.591934375,51.1606519978,609.6 0.5915175691,51.1572341668,609.6 0.5916618315,51.1538074997,609.6 0.5923655088999999,51.150408318,609.6 0.5936210222,51.14707264390001,609.6 0.5954149519,51.1438358191,609.6 0.5977281846,51.1407321305,609.6 0.6005361204,51.1377944485,609.6 0.6038089363,51.13505387880001,609.6 0.6075119051,51.1325394351,609.6 0.6116057653,51.1302777326,609.6 0.6160471368,51.12829270739999,609.6 0.6207889809,51.1266053649,609.6 0.6257810968999999,51.1252335582,609.6 0.6309706512,51.12419180039999,609.6 0.6363027343,51.123491112,609.6 0.6417209384,51.123138905,609.6 0.6471679504,51.123138905,609.6 0.6525861545,51.123491112,609.6 0.6579182377,51.12419180039999,609.6 0.663107792,51.1252335582,609.6 0.668099908,51.1266053649,609.6 0.6728417521,51.12829270739999,609.6 0.6772831236,51.1302777326,609.6 0.6813769837,51.1325394351,609.6 0.6850799526,51.13505387880001,609.6 0.6883527685,51.1377944485,609.6 0.6911607043,51.1407321305,609.6 0.693473937,51.1438358191,609.6 0.6952678667,51.14707264390001,609.6 0.69652338,51.150408318,609.6 0.6972270574,51.1538074997,609.6 0.6973713198,51.1572341668,609.6 0.6969545139,51.1606519978,609.6 0.6959809353,51.16402475700001,609.6 0.6944607878,51.1673166787,609.6 0.6924100805,51.1704928469,609.6 0.6898504622,51.1735195665,609.6 0.6868089958,51.17636472139999,609.6 0.6833178747,51.17899811629999,609.6 0.6794140829999999,51.1813917985,609.6 0.6751390051,51.1835203555,609.6 0.6705379861,51.1853611865,609.6 0.6656598506,51.1868947429,609.6 0.6605563826,51.1881047377,609.6 0.6552817736,51.188978319,609.6 0.6498920438,51.1895062075,609.6 0.6444444444,51.1896827956,609.6 + + + + +
+ + EGRU140B LASHENDEN/HEADCORN RWY 10 + 510953N 0003359E -
511024N 0003412E -
511009N 0003544E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to
510937N 0003531E -
510953N 0003359E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5663138889,51.1645833333,609.6 0.5918729444,51.1603403333,609.6 0.5926518716,51.16330463360001,609.6 0.5938527671,51.1662126983,609.6 0.5954659167,51.1690408333,609.6 0.5699777778,51.1732722222,609.6 0.5663138889,51.1645833333,609.6 + + + + +
+ + EGRU140C LASHENDEN/HEADCORN RWY 28 + 510853N 0004319E -
510821N 0004306E -
510836N 0004136E thence anti-clockwise by the arc of a circle radius 2 NM centred on 510923N 0003840E to
510908N 0004149E -
510853N 0004319E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7218944443999999,51.1479583333,609.6 0.6969505833,51.15213019440001,609.6 0.6961247654,51.1491710648,609.6 0.6948783343,51.1462707894,609.6 0.6932215,51.1434529722,609.6 0.7182361111,51.1392694444,609.6 0.7218944443999999,51.1479583333,609.6 + + + + +
+ + EGRU141A EARLS COLNE + A circle, 2 NM radius, centred at 515452N 0004057E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6825,51.9477340257,609.6 0.6769610427,51.947557457,609.6 0.6714809291,51.9470296268,609.6 0.6661178735,51.9461561423,609.6 0.6609288387,51.94494628230001,609.6 0.6559689273,51.94341289800001,609.6 0.6512907936,51.94157227549999,609.6 0.6469440818,51.9394439619,609.6 0.6429748979,51.9370505568,609.6 0.6394253193,51.93441747070001,609.6 0.636332949,51.9315726541,609.6 0.6337305176,51.9285462996,609.6 0.631645539,51.9253705205,609.6 0.6301000212,51.9220790084,609.6 0.6291102374,51.9187066755,609.6 0.6286865582,51.9152892834,609.6 0.6288333463,51.9118630633,609.6 0.6295489163,51.908464332,609.6 0.6308255577,51.90512910650001,609.6 0.632649622,51.9018927233,609.6 0.635001672,51.8987894642,609.6 0.6378566928,51.8958521937,609.6 0.6411843597,51.8931120127,609.6 0.6449493626,51.8905979296,609.6 0.6491117818,51.8883365545,609.6 0.6536275115,51.8863518193,609.6 0.6584487265,51.8846647251,609.6 0.6635243874,51.8832931215,609.6 0.668800779,51.8822515187,609.6 0.6742220758,51.8815509349,609.6 0.6797309292,51.8811987806,609.6 0.6852690708,51.8811987806,609.6 0.6907779241999999,51.8815509349,609.6 0.696199221,51.8822515187,609.6 0.7014756126,51.8832931215,609.6 0.7065512735000001,51.8846647251,609.6 0.7113724885,51.8863518193,609.6 0.7158882182,51.8883365545,609.6 0.7200506374,51.8905979296,609.6 0.7238156403,51.8931120127,609.6 0.7271433072,51.8958521937,609.6 0.729998328,51.8987894642,609.6 0.7323503780000001,51.9018927233,609.6 0.7341744422999998,51.90512910650001,609.6 0.7354510837,51.908464332,609.6 0.7361666536999999,51.9118630633,609.6 0.7363134417999999,51.9152892834,609.6 0.7358897625999999,51.9187066755,609.6 0.7348999788,51.9220790084,609.6 0.733354461,51.9253705205,609.6 0.7312694824,51.9285462996,609.6 0.728667051,51.9315726541,609.6 0.7255746807,51.93441747070001,609.6 0.7220251021,51.9370505568,609.6 0.7180559182000001,51.9394439619,609.6 0.7137092064,51.94157227549999,609.6 0.7090310727,51.94341289800001,609.6 0.7040711613,51.94494628230001,609.6 0.6988821265,51.9461561423,609.6 0.6935190709,51.9470296268,609.6 0.6880389573,51.947557457,609.6 0.6825,51.9477340257,609.6 + + + + +
+ + EGRU141B EARLS COLNE RWY 06 + 515309N 0003708E -
515337N 0003642E -
515405N 0003759E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515337N 0003826E -
515309N 0003708E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6188194444,51.8858888889,609.6 0.6405008056,51.89362883329999,609.6 0.6376370069,51.8960555344,609.6 0.6351382452,51.8986320512,609.6 0.6330249167000001,51.90133741670001,609.6 0.6115694444000001,51.8936777778,609.6 0.6188194444,51.8858888889,609.6 + + + + +
+ + EGRU141C EARLS COLNE RWY 24 + 515631N 0004450E -
515603N 0004516E -
515535N 0004358E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515604N 0004332E -
515631N 0004450E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7473027778,51.94202500000001,609.6 0.7256713333,51.9343375,609.6 0.7283957123,51.9318493242,609.6 0.7307458014,51.9292193892,609.6 0.7327025,51.92646913890001,609.6 0.7545583333,51.93423611109999,609.6 0.7473027778,51.94202500000001,609.6 + + + + +
+ + EGRU142A SOUTHEND + A circle, 2.5 NM radius, centred at 513413N 0004136E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6933333333,51.6118921753,609.6 0.6871661804,51.6117144943,609.6 0.6810517867,51.6111829714,609.6 0.6750424567,51.6103021536,609.6 0.6691895887,51.6090795755,609.6 0.6635432321,51.6075256945,609.6 0.6581516565,51.60565380079999,609.6 0.6530609364,51.6034799024,609.6 0.648314556,51.6010225879,609.6 0.6439530358,51.5983028658,609.6 0.6400135863999999,51.5953439844,609.6 0.6365297913,51.5921712314,609.6 0.6335313205000001,51.5888117171,609.6 0.63104368,51.5852941413,609.6 0.6290879964,51.5816485477,609.6 0.62768084,51.5779060657,609.6 0.6268340873,51.5740986447,609.6 0.6265548244,51.5702587803,609.6 0.6268452906,51.5664192368,609.6 0.6277028650000001,51.5626127676,609.6 0.6291200932,51.5588718361,609.6 0.6310847554,51.5552283386,609.6 0.6335799758,51.5517133334,609.6 0.6365843696,51.54835677650001,609.6 0.6400722293,51.5451872669,609.6 0.6440137460000001,51.5422318046,609.6 0.6483752663,51.53951556090001,609.6 0.6531195793,51.5370616655,609.6 0.6582062349,51.5348910106,609.6 0.6635918876,51.5330220742,609.6 0.6692306642,51.5314707638,609.6 0.6750745535,51.5302502819,609.6 0.6810738118,51.5293710145,609.6 0.6871773836,51.5288404435,609.6 0.6933333333,51.5286630835,609.6 0.699489283,51.5288404435,609.6 0.7055928549,51.5293710145,609.6 0.7115921131,51.5302502819,609.6 0.7174360023999999,51.5314707638,609.6 0.7230747791000001,51.5330220742,609.6 0.7284604317,51.5348910106,609.6 0.7335470874,51.5370616655,609.6 0.7382914004,51.53951556090001,609.6 0.7426529206000001,51.5422318046,609.6 0.7465944374000001,51.5451872669,609.6 0.7500822969999998,51.54835677650001,609.6 0.7530866907999999,51.5517133334,609.6 0.7555819112,51.5552283386,609.6 0.7575465735,51.5588718361,609.6 0.7589638016,51.5626127676,609.6 0.7598213761,51.5664192368,609.6 0.7601118423,51.5702587803,609.6 0.7598325793,51.5740986447,609.6 0.7589858267,51.5779060657,609.6 0.7575786702,51.5816485477,609.6 0.7556229865999999,51.5852941413,609.6 0.7531353462,51.5888117171,609.6 0.7501368754,51.5921712314,609.6 0.7466530802,51.5953439844,609.6 0.7427136308999999,51.5983028658,609.6 0.7383521107,51.6010225879,609.6 0.7336057302,51.6034799024,609.6 0.7285150102,51.60565380079999,609.6 0.7231234345000001,51.6075256945,609.6 0.7174770779,51.6090795755,609.6 0.7116242099,51.6103021536,609.6 0.7056148799,51.6111829714,609.6 0.6995004862999999,51.6117144943,609.6 0.6933333333,51.6118921753,609.6 + + + + +
+ + EGRU142B SOUTHEND RWY 05 + 513209N 0003745E -
513236N 0003714E -
513259N 0003807E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513233N 0003837E -
513209N 0003745E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6291166667,51.53595555559999,609.6 0.6436260556,51.54249894439999,609.6 0.6405434667,51.544803412,609.6 0.637734927,51.5472403342,609.6 0.6352150556,51.5497970556,609.6 0.6206805556,51.5432416667,609.6 0.6291166667,51.53595555559999,609.6 + + + + +
+ + EGRU142C SOUTHEND RWY 23 + 513615N 0004523E -
513549N 0004553E -
513527N 0004505E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513554N 0004434E -
513615N 0004523E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7563638888999999,51.6042944444,609.6 0.7428335,51.5982206389,609.6 0.7459369184,51.5959248333,609.6 0.7487662855,51.5934956228,609.6 0.7513069167,51.5909456667,609.6 0.7648138889000001,51.5970083333,609.6 0.7563638888999999,51.6042944444,609.6 + + + + +
+ + EGRU143A LONDON HELIPORT + A circle, 2 NM radius, centred at 512812N 0001046W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1795388889,51.50322266999999,609.6 -0.1850237897,51.5030460899,609.6 -0.1904504231,51.5025182256,609.6 -0.1957611449,51.5016446845,609.6 -0.2008995498,51.5004347457,609.6 -0.2058110744,51.4989012607,609.6 -0.2104435795,51.4970605163,609.6 -0.2147479056,51.4949320603,609.6 -0.2186783971,51.49253849309999,609.6 -0.2221933866,51.4899052263,609.6 -0.2252556374,51.4870602117,609.6 -0.2278327366,51.4840336435,609.6 -0.2298974372,51.48085763660001,609.6 -0.2314279437,51.47756588469999,609.6 -0.2324081392,51.4741933023,609.6 -0.2328277518,51.4707756531,609.6 -0.2326824584,51.46734917130001,609.6 -0.2319739255,51.46395017609999,609.6 -0.2307097858,51.4606146879,609.6 -0.2289035523,51.4573780459,609.6 -0.2265744705,51.4542745352,609.6 -0.22374731,51.4513370235,609.6 -0.2204520984,51.4485966148,609.6 -0.2167238008,51.4460823203,609.6 -0.2126019478,51.44382075330001,609.6 -0.2081302155,51.44183584809999,609.6 -0.2033559639,51.4401486084,609.6 -0.1983297361,51.4387768857,609.6 -0.1931047256,51.43773519200001,609.6 -0.187736216,51.4370345469,609.6 -0.1822809993,51.4366823617,609.6 -0.1767967785,51.4366823617,609.6 -0.1713415617,51.4370345469,609.6 -0.1659730521,51.43773519200001,609.6 -0.1607480417,51.4387768857,609.6 -0.1557218139,51.4401486084,609.6 -0.1509475623,51.44183584809999,609.6 -0.14647583,51.44382075330001,609.6 -0.142353977,51.4460823203,609.6 -0.1386256794,51.4485966148,609.6 -0.1353304678,51.4513370235,609.6 -0.1325033072,51.4542745352,609.6 -0.1301742255,51.4573780459,609.6 -0.128367992,51.4606146879,609.6 -0.1271038523,51.46395017609999,609.6 -0.1263953194,51.46734917130001,609.6 -0.126250026,51.4707756531,609.6 -0.1266696386,51.4741933023,609.6 -0.1276498341,51.47756588469999,609.6 -0.1291803406,51.48085763660001,609.6 -0.1312450412,51.4840336435,609.6 -0.1338221404,51.4870602117,609.6 -0.1368843911,51.4899052263,609.6 -0.1403993807,51.49253849309999,609.6 -0.1443298721,51.4949320603,609.6 -0.1486341983,51.4970605163,609.6 -0.1532667033,51.4989012607,609.6 -0.158178228,51.5004347457,609.6 -0.1633166329,51.5016446845,609.6 -0.1686273547,51.5025182256,609.6 -0.1740539881,51.5030460899,609.6 -0.1795388889,51.50322266999999,609.6 + + + + +
+ + EGRU145A KENLEY + A circle, 2 NM radius, centred at 511821N 0000536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0934361111,51.33925416229999,609.6 -0.09890142070000001,51.33907757800001,609.6 -0.1043086718,51.33854970110001,609.6 -0.1096004267,51.33767613900001,609.6 -0.1147204823,51.3364661709,609.6 -0.1196144705,51.3349326486,609.6 -0.1242304386,51.333091859,609.6 -0.1285194033,51.3309633502,609.6 -0.1324358716,51.3285697229,609.6 -0.1359383252,51.3259363892,609.6 -0.1389896597,51.3230913013,609.6 -0.1415575778,51.320064654,609.6 -0.143614929,51.3168885628,609.6 -0.1451399949,51.3135967222,609.6 -0.1461167151,51.31022404739999,609.6 -0.1465348537,51.30680630320001,609.6 -0.1463901019,51.3033797245,609.6 -0.1456841192,51.2999806319,609.6 -0.1444245102,51.2966450465,609.6 -0.1426247389,51.2934083089,609.6 -0.1403039812,51.2903047052,609.6 -0.1374869178,51.2873671045,609.6 -0.1342034687,51.2846266116,609.6 -0.1304884741,51.2821122391,609.6 -0.1263813233,51.27985060129999,609.6 -0.1219255368,51.2778656334,609.6 -0.117168306,51.2761783399,609.6 -0.1121599941,51.2748065733,609.6 -0.1069536056,51.27376484600001,609.6 -0.1016042276,51.27306417829999,609.6 -0.0961684503,51.2727119817,609.6 -0.090703772,51.2727119817,609.6 -0.08526799459999999,51.27306417829999,609.6 -0.07991861660000001,51.27376484600001,609.6 -0.0747122281,51.2748065733,609.6 -0.0697039163,51.2761783399,609.6 -0.0649466854,51.2778656334,609.6 -0.06049089900000001,51.27985060129999,609.6 -0.0563837481,51.2821122391,609.6 -0.05266875349999999,51.2846266116,609.6 -0.04938530449999999,51.2873671045,609.6 -0.046568241,51.2903047052,609.6 -0.0442474834,51.2934083089,609.6 -0.0424477121,51.2966450465,609.6 -0.0411881031,51.2999806319,609.6 -0.0404821204,51.3033797245,609.6 -0.0403373686,51.30680630320001,609.6 -0.0407555071,51.31022404739999,609.6 -0.0417322274,51.3135967222,609.6 -0.0432572932,51.3168885628,609.6 -0.0453146444,51.320064654,609.6 -0.04788256250000001,51.3230913013,609.6 -0.050933897,51.3259363892,609.6 -0.0544363506,51.3285697229,609.6 -0.05835281900000001,51.3309633502,609.6 -0.0626417836,51.333091859,609.6 -0.0672577518,51.3349326486,609.6 -0.07215174000000001,51.3364661709,609.6 -0.0772717955,51.33767613900001,609.6 -0.0825635504,51.33854970110001,609.6 -0.0879708015,51.33907757800001,609.6 -0.0934361111,51.33925416229999,609.6 + + + + +
+ + EGRU146A UPAVON + A circle, 2 NM radius, centred at 511710N 0014652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7810361111,51.3194987197,609.6 -1.7864990728,51.3193221349,609.6 -1.791904001,51.3187942564,609.6 -1.7971934828,51.3179206918,609.6 -1.8023113392,51.3167107202,609.6 -1.8072032258,51.3151771934,609.6 -1.8118172121,51.31333639830001,609.6 -1.8161043357,51.31120788320001,609.6 -1.8200191235,51.3088142487,609.6 -1.8235200746,51.30618090680001,609.6 -1.8265701009,51.3033358101,609.6 -1.8291369187,51.3003091533,609.6 -1.8311933891,51.29713305189999,609.6 -1.8327178029,51.2938412006,609.6 -1.8336941066,51.29046851470001,609.6 -1.8341120685,51.287050759,609.6 -1.8339673816,51.2836241687,609.6 -1.8332617045,51.2802250642,609.6 -1.8320026385,51.27688946710001,609.6 -1.8302036416,51.2736527181,609.6 -1.8278838816,51.2705491032,609.6 -1.8250680283,51.2676114917,609.6 -1.8217859889,51.2648709887,609.6 -1.8180725886,51.2623566068,609.6 -1.8139671997,51.2600949604,609.6 -1.8095133244,51.2581099849,609.6 -1.8047581334,51.256422685,609.6 -1.7997519687,51.255050913,609.6 -1.7945478119,51.2540091818,609.6 -1.7892007268,51.25330851129999,609.6 -1.7837672792,51.2529563133,609.6 -1.778304943,51.2529563133,609.6 -1.7728714954,51.25330851129999,609.6 -1.7675244103,51.2540091818,609.6 -1.7623202535,51.255050913,609.6 -1.7573140888,51.256422685,609.6 -1.7525588979,51.2581099849,609.6 -1.7481050225,51.2600949604,609.6 -1.7439996337,51.2623566068,609.6 -1.7402862334,51.2648709887,609.6 -1.737004194,51.2676114917,609.6 -1.7341883406,51.2705491032,609.6 -1.7318685806,51.2736527181,609.6 -1.7300695837,51.27688946710001,609.6 -1.7288105177,51.2802250642,609.6 -1.7281048407,51.2836241687,609.6 -1.7279601537,51.287050759,609.6 -1.7283781156,51.29046851470001,609.6 -1.7293544194,51.2938412006,609.6 -1.7308788332,51.29713305189999,609.6 -1.7329353036,51.3003091533,609.6 -1.7355021213,51.3033358101,609.6 -1.7385521476,51.30618090680001,609.6 -1.7420530988,51.3088142487,609.6 -1.7459678865,51.31120788320001,609.6 -1.7502550102,51.31333639830001,609.6 -1.7548689964,51.3151771934,609.6 -1.759760883,51.3167107202,609.6 -1.7648787395,51.3179206918,609.6 -1.7701682212,51.3187942564,609.6 -1.7755731495,51.3193221349,609.6 -1.7810361111,51.3194987197,609.6 + + + + +
+ + EGRU147A WESTON ON THE GREEN + A circle, 2 NM radius, centred at 515245N 0011304W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.217775,51.9124147822,609.6 -1.2233096109,51.9122382126,609.6 -1.2287854244,51.9117103797,609.6 -1.2341442722,51.9108368907,609.6 -1.2393292361,51.9096270245,609.6 -1.2442852569,51.90809363219999,609.6 -1.2489597219,51.906253,609.6 -1.2533030257,51.9041246752,609.6 -1.2572690985,51.9017312573,609.6 -1.260815896,51.8990981568,609.6 -1.2639058446,51.8962533245,609.6 -1.2665062392,51.8932269531,609.6 -1.2685895874,51.8900511559,609.6 -1.2701338983,51.8867596248,609.6 -1.2711229111,51.88338727210001,609.6 -1.2715462634,51.8799698596,609.6 -1.2713995955,51.8765436188,609.6 -1.2706845913,51.8731448665,609.6 -1.2694089551,51.8698096202,609.6 -1.2675863246,51.8665732165,609.6 -1.2652361213,51.8634699373,609.6 -1.2623833407,51.86053264780001,609.6 -1.2590582833,51.85779244870001,609.6 -1.2552962317,51.8552783487,609.6 -1.2511370741,51.85301695849999,609.6 -1.246624882,51.8510322098,609.6 -1.2418074431,51.849345104,609.6 -1.2367357568,51.8479734909,609.6 -1.2314634964,51.8469318809,609.6 -1.2260464439,51.8462312922,609.6 -1.2205419031,51.8458791355,609.6 -1.2150080969,51.8458791355,609.6 -1.2095035561,51.8462312922,609.6 -1.2040865036,51.8469318809,609.6 -1.1988142432,51.8479734909,609.6 -1.1937425569,51.849345104,609.6 -1.188925118,51.8510322098,609.6 -1.1844129259,51.85301695849999,609.6 -1.1802537683,51.8552783487,609.6 -1.1764917167,51.85779244870001,609.6 -1.1731666593,51.86053264780001,609.6 -1.1703138787,51.8634699373,609.6 -1.1679636754,51.8665732165,609.6 -1.1661410449,51.8698096202,609.6 -1.1648654087,51.8731448665,609.6 -1.1641504045,51.8765436188,609.6 -1.1640037366,51.8799698596,609.6 -1.1644270889,51.88338727210001,609.6 -1.1654161017,51.8867596248,609.6 -1.1669604126,51.8900511559,609.6 -1.1690437608,51.8932269531,609.6 -1.1716441554,51.8962533245,609.6 -1.174734104,51.8990981568,609.6 -1.1782809015,51.9017312573,609.6 -1.1822469743,51.9041246752,609.6 -1.1865902781,51.906253,609.6 -1.1912647431,51.90809363219999,609.6 -1.1962207639,51.9096270245,609.6 -1.2014057278,51.9108368907,609.6 -1.2067645756,51.9117103797,609.6 -1.2122403891,51.9122382126,609.6 -1.217775,51.9124147822,609.6 + + + + +
+ + EGRU148A LITTLE RISSINGTON + A circle, 2 NM radius, centred at 515202N 0014139W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6941888889,51.9003787396,609.6 -1.6997220206,51.9002021697,609.6 -1.7051963708,51.8996743359,609.6 -1.7105537866,51.8988008453,609.6 -1.7157373652,51.89759097699999,609.6 -1.720692062,51.8960575819,609.6 -1.7253652785,51.8942169465,609.6 -1.7297074225,51.89208861779999,609.6 -1.7336724366,51.8896951955,609.6 -1.7372182877,51.8870620902,609.6 -1.7403074122,51.88421725250001,609.6 -1.7429071136,51.8811908754,609.6 -1.744989907,51.878015072,609.6 -1.7465338071,51.8747235344,609.6 -1.7475225576,51.871351175,609.6 -1.7479457987,51.8679337555,609.6 -1.7477991716,51.8645075076,609.6 -1.74708436,51.8611087482,609.6 -1.7458090659,51.8577734948,609.6 -1.7439869233,51.8545370841,609.6 -1.7416373485,51.8514337981,609.6 -1.7387853301,51.848496502,609.6 -1.7354611608,51.8457562968,609.6 -1.7317001135,51.8432421911,609.6 -1.7275420659,51.84098079570001,609.6 -1.7230310777,51.83899604240001,609.6 -1.7182149238,51.8373089327,609.6 -1.7131445901,51.8359373164,609.6 -1.7078737356,51.83489570390001,609.6 -1.7024581275,51.8341951135,609.6 -1.6969550543,51.8338429559,609.6 -1.6914227235,51.8338429559,609.6 -1.6859196503,51.8341951135,609.6 -1.6805040421,51.83489570390001,609.6 -1.6752331877,51.8359373164,609.6 -1.670162854,51.8373089327,609.6 -1.6653467001,51.83899604240001,609.6 -1.6608357118,51.84098079570001,609.6 -1.6566776643,51.8432421911,609.6 -1.6529166169,51.8457562968,609.6 -1.6495924477,51.848496502,609.6 -1.6467404293,51.8514337981,609.6 -1.6443908545,51.8545370841,609.6 -1.6425687119,51.8577734948,609.6 -1.6412934178,51.8611087482,609.6 -1.6405786061,51.8645075076,609.6 -1.6404319791,51.8679337555,609.6 -1.6408552202,51.871351175,609.6 -1.6418439707,51.8747235344,609.6 -1.6433878708,51.878015072,609.6 -1.6454706642,51.8811908754,609.6 -1.6480703656,51.88421725250001,609.6 -1.6511594901,51.8870620902,609.6 -1.6547053411,51.8896951955,609.6 -1.6586703553,51.89208861779999,609.6 -1.6630124993,51.8942169465,609.6 -1.6676857158,51.8960575819,609.6 -1.6726404126,51.89759097699999,609.6 -1.6778239912,51.8988008453,609.6 -1.6831814069,51.8996743359,609.6 -1.6886557571,51.9002021697,609.6 -1.6941888889,51.9003787396,609.6 + + + + +
+ + EGRU148B LITTLE RISSINGTON RWY 04 + 514928N 0014421W -
514948N 0014502W -
515038N 0014358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515018N 0014317W -
514928N 0014421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7391218333,51.8243148333,609.6 -1.7213525556,51.8383616389,609.6 -1.7254230493,51.8399944628,609.6 -1.7292396587,51.8418478204,609.6 -1.7327713333,51.8439066389,609.6 -1.7505336944,51.8298625,609.6 -1.7391218333,51.8243148333,609.6 + + + + +
+ + EGRU148C LITTLE RISSINGTON RWY 22 + 515435N 0013857W -
515415N 0013816W -
515325N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515345N 0014001W -
515435N 0013857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6491845278,51.9098425278,609.6 -1.6669975556,51.89581225,609.6 -1.6629237494,51.8941777929,609.6 -1.6591049889,51.89232265580001,609.6 -1.6555723889,51.89026197219999,609.6 -1.6377523889,51.90429491670001,609.6 -1.6491845278,51.9098425278,609.6 + + + + +
+ + EGRU148D LITTLE RISSINGTON RWY 09 + 515133N 0014621W -
515205N 0014626W -
515210N 0014452W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515138N 0014449W -
515133N 0014621W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7725545278,51.8591138056,609.6 -1.7468936389,51.8604959167,609.6 -1.7476408861,51.8634648455,609.6 -1.7479527579,51.8664633953,609.6 -1.7478266389,51.8694671389,609.6 -1.7737993056,51.86806827780001,609.6 -1.7725545278,51.8591138056,609.6 + + + + +
+ + EGRU148E LITTLE RISSINGTON RWY 27 + 515236N 0013649W -
515204N 0013645W -
515158N 0013826W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515230N 0013831W -
515236N 0013649W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6136181389,51.8766028056,609.6 -1.6419936111,51.8751070833,609.6 -1.641039975,51.8721608815,609.6 -1.6405194626,51.869173453,609.6 -1.64043625,51.86616913890001,609.6 -1.6123731111,51.8676483611,609.6 -1.6136181389,51.8766028056,609.6 + + + + +
+ + EGRU148F LITTLE RISSINGTON RWY 13 + 515336N 0014536W -
515400N 0014501W -
515326N 0014357W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515300N 0014429W -
515336N 0014536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7599274722,51.8932725278,609.6 -1.7412547778,51.8831991667,609.6 -1.738709554,51.8857675435,609.6 -1.735799195,51.8881829232,609.6 -1.7325475278,51.8904255,609.6 -1.7503725833,51.9000425,609.6 -1.7599274722,51.8932725278,609.6 + + + + +
+ + EGRU148G LITTLE RISSINGTON RWY 31 + 515008N 0013751W -
514943N 0013825W -
515025N 0013943W thence anti-clockwise by the arc of a circle radius 2 NM centred on 515202N 0014139W to
515048N 0013906W -
515008N 0013751W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6308653333,51.8354350556,609.6 -1.6516788333,51.84670925,609.6 -1.6548287542,51.8444133462,609.6 -1.6583005968,51.8423031413,609.6 -1.6620659167,51.8403958889,609.6 -1.6404065278,51.8286650278,609.6 -1.6308653333,51.8354350556,609.6 + + + + +
+ + EGRU149 HMP ASHFIELD + 512911N 0022623W -
512908N 0022602W -
512901N 0022556W -
512852N 0022556W -
512843N 0022602W -
512836N 0022619W -
512841N 0022644W -
512854N 0022652W -
512907N 0022641W -
512911N 0022623W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 405 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4396638889,51.4865194444,274.32 -2.4446388889,51.485325,274.32 -2.4478944444,51.4817361111,274.32 -2.4456416667,51.4779722222,274.32 -2.438575,51.47657222219999,274.32 -2.4337638889,51.47851944439999,274.32 -2.4321583333,51.48111666669999,274.32 -2.4321638889,51.4834777778,274.32 -2.4338861111,51.4854361111,274.32 -2.4396638889,51.4865194444,274.32 + + + + +
+ + EGRU150 HMP AYLESBURY + 514938N 0004807W -
514935N 0004742W -
514916N 0004724W -
514904N 0004732W -
514857N 0004807W -
514914N 0004830W -
514926N 0004829W -
514938N 0004807W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 311 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8018638889,51.8272222222,243.84 -0.8080638889,51.8240194444,243.84 -0.8083861111,51.8205972222,243.84 -0.8018833332999999,51.8157416667,243.84 -0.7922305556,51.8176833333,243.84 -0.7900166667,51.8210444444,243.84 -0.7949638888999999,51.82650000000001,243.84 -0.8018638889,51.8272222222,243.84 + + + + +
+ + EGRU151 HMP BELMARSH/THAMESIDE/ISIS + 513012N 0000557E -
512942N 0000624E -
512930N 0000550E -
512918N 0000540E -
512927N 0000450E -
512952N 0000501E -
513012N 0000557E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 16 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0990305556,51.5032916667,152.4 0.08349444440000001,51.4976583333,152.4 0.08043333330000001,51.4909166667,152.4 0.0945611111,51.4882305556,152.4 0.097125,51.4915305556,152.4 0.1065527778,51.4949638889,152.4 0.0990305556,51.5032916667,152.4 + + + + +
+ + EGRU152 HMP BRISTOL + 512909N 0023540W -
512905N 0023520W -
512857N 0023505W -
512849N 0023503W -
512837N 0023512W -
512834N 0023540W -
512848N 0023602W -
512901N 0023600W -
512909N 0023540W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 206 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5945583333,51.48574444439999,213.36 -2.5999805556,51.4835722222,213.36 -2.6006527778,51.4800527778,213.36 -2.5943277778,51.4762111111,213.36 -2.5866972222,51.4770777778,213.36 -2.5841138889,51.4802305556,213.36 -2.5845861111,51.4824888889,213.36 -2.5889111111,51.4847722222,213.36 -2.5945583333,51.48574444439999,213.36 + + + + +
+ + EGRU153 HMP BRIXTON + 512722N 0000738W -
512718N 0000710W -
512709N 0000703W -
512656N 0000707W -
512650N 0000721W -
512653N 0000755W -
512714N 0000758W -
512722N 0000738W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 125 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1273222222,51.4562194444,182.88 -0.132775,51.4538527778,182.88 -0.132025,51.4481638889,182.88 -0.1223611111,51.4472388889,182.88 -0.1186333333,51.4488194444,182.88 -0.1174055556,51.4525472222,182.88 -0.1195583333,51.4551111111,182.88 -0.1273222222,51.4562194444,182.88 + + + + +
+ + EGRU154 HMP BRONZEFIELD + 512610N 0002935W -
512618N 0002841W -
512554N 0002832W -
512544N 0002845W -
512541N 0002907W -
512549N 0002925W -
512610N 0002935W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 53 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4930166667,51.4362277778,152.4 -0.4903944444,51.4301416667,152.4 -0.4851722222,51.42807222220001,152.4 -0.4792944444,51.4289388889,152.4 -0.4755583333,51.43160277779999,152.4 -0.4780916667,51.4384027778,152.4 -0.4930166667,51.4362277778,152.4 + + + + +
+ + EGRU155 HMP BULLINGDON + 515113N 0010603W -
515114N 0010521W -
515103N 0010505W -
515049N 0010507W -
515037N 0010526W -
515038N 0010553W -
515050N 0010610W -
515113N 0010603W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 267 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1007305556,51.8536888889,213.36 -1.1028972222,51.84718055559999,213.36 -1.0980777778,51.84375,213.36 -1.0904388889,51.8436166667,213.36 -1.0851861111,51.8468194444,213.36 -1.0848166667,51.8508305556,213.36 -1.0891916667,51.85380833330001,213.36 -1.1007305556,51.8536888889,213.36 + + + + +
+ + EGRU156 HMP CARDIFF + 512910N 0031002W -
512854N 0030934W -
512834N 0030952W -
512831N 0031011W -
512844N 0031031W -
512902N 0031033W -
512910N 0031002W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 39 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1672138889,51.48604722219999,152.4 -3.1757305556,51.4838527778,152.4 -3.175252777799999,51.4788194444,152.4 -3.1696805556,51.475225,152.4 -3.1643611111,51.4761972222,152.4 -3.1593388889,51.4816305556,152.4 -3.1672138889,51.48604722219999,152.4 + + + + +
+ + EGRU157 HMP CHELMSFORD + 514431N 0002858E -
514416N 0002945E -
514359N 0002948E -
514351N 0002936E -
514352N 0002909E -
514404N 0002833E -
514431N 0002858E
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 135 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4828416667,51.74201111109999,182.88 0.4758444444,51.73457222220001,182.88 0.4857611110999999,51.73124444439999,182.88 0.4934583333,51.7308777778,182.88 0.4965583332999999,51.7330944444,182.88 0.4958222222,51.7377777778,182.88 0.4828416667,51.74201111109999,182.88 + + + + +
+ + EGRU158 HMP COLDINGLEY + 511938N 0003849W -
511937N 0003818W -
511917N 0003756W -
511858N 0003841W -
511917N 0003910W -
511938N 0003849W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 174 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6469388889,51.32713333329999,182.88 -0.6526472222,51.3213472222,182.88 -0.6445972222,51.3159916667,182.88 -0.6323444444,51.32135555559999,182.88 -0.6382083333,51.3268527778,182.88 -0.6469388889,51.32713333329999,182.88 + + + + +
+ + EGRU159 HMP DOWNVIEW/HIGH DOWN + 512036N 0001131W -
512039N 0001059W -
512019N 0001050W -
511952N 0001055W -
511948N 0001137W -
511959N 0001154W -
512027N 0001150W -
512036N 0001131W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 457 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1918888889,51.34335,274.32 -0.1973305556,51.34089999999999,274.32 -0.1983277778,51.3329555556,274.32 -0.1936833333,51.33009444439999,274.32 -0.1818777778,51.3310472222,274.32 -0.1805555556,51.3386166667,274.32 -0.1830305556,51.3442861111,274.32 -0.1918888889,51.34335,274.32 + + + + +
+ + EGRU160 HMP EAST SUTTON PARK + 511311N 0003654E -
511313N 0003731E -
511249N 0003733E -
511235N 0003642E -
511301N 0003632E -
511311N 0003654E
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 376 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6149277778,51.2196083333,243.84 0.6088027778,51.2168722222,243.84 0.6115416667,51.20981666670001,243.84 0.6257305556,51.213475,243.84 0.6254055556,51.2202638889,243.84 0.6149277778,51.2196083333,243.84 + + + + +
+ + EGRU161 HMP EASTWOOD PARK + 513819N 0022840W -
513823N 0022800W -
513822N 0022740W -
513803N 0022723W -
513751N 0022754W -
513747N 0022829W -
513819N 0022840W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4776472222,51.6386305556,182.88 -2.4745916667,51.6297,182.88 -2.4648611111,51.6309111111,182.88 -2.4564555556,51.6342583333,182.88 -2.4611111111,51.6395611111,182.88 -2.4666166667,51.6397694444,182.88 -2.4776472222,51.6386305556,182.88 + + + + +
+ + EGRU162 HMP ERLESTOKE + 511726N 0020243W -
511728N 0020206W -
511703N 0020205W -
511643N 0020217W -
511650N 0020308W -
511712N 0020324W -
511726N 0020243W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 360 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0452722222,51.29065277779999,243.84 -2.0567666667,51.2865527778,243.84 -2.0523444444,51.28052777780001,243.84 -2.0381527778,51.27865833330001,243.84 -2.0346833333,51.2842861111,243.84 -2.0350694444,51.29121388890001,243.84 -2.0452722222,51.29065277779999,243.84 + + + + +
+ + EGRU163 HMP FELTHAM + 512644N 0002615W -
512640N 0002532W -
512559N 0002547W -
512607N 0002647W -
512639N 0002641W -
512644N 0002615W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 62 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4374555555999999,51.4456916667,152.4 -0.4445888889,51.4440722222,152.4 -0.4464194444,51.4351611111,152.4 -0.4298361111,51.4329861111,152.4 -0.4255777777999999,51.4443638889,152.4 -0.4374555555999999,51.4456916667,152.4 + + + + +
+ + EGRU164 HMP GRENDON + 515354N 0010045W -
515352N 0010002W -
515339N 0005949W -
515321N 0005949W -
515310N 0010013W -
515317N 0010046W -
515332N 0010050W -
515354N 0010045W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 296 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0123694444,51.8984361111,213.36 -1.01375,51.8922777778,213.36 -1.0127555556,51.8879388889,213.36 -1.0036888889,51.8861833333,213.36 -0.9968944444,51.8892388889,213.36 -0.9969638889,51.8942055556,213.36 -1.0004833333,51.89774166670001,213.36 -1.0123694444,51.8984361111,213.36 + + + + +
+ + EGRU165 HMP HUNTERCOMBE + 513536N 0010124W -
513528N 0010033W -
513455N 0010046W -
513504N 0010142W -
513536N 0010124W
Upper limit: 1100 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 691 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0232222222,51.5932361111,335.28 -1.0283555556,51.5845388889,335.28 -1.0128361111,51.58186944440001,335.28 -1.0091694444,51.59106944439999,335.28 -1.0232222222,51.5932361111,335.28 + + + + +
+ + EGRU166 HMP MAIDSTONE + 511709N 0003128E -
511642N 0003202E -
511622N 0003124E -
511648N 0003046E -
511709N 0003128E
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 123 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5243527778,51.28575555560001,182.88 0.5127555556,51.2800194444,182.88 0.5232944443999999,51.2726805556,182.88 0.5339416667,51.2783527778,182.88 0.5243527778,51.28575555560001,182.88 + + + + +
+ + EGRU167 HMP PARC + 513207N 0033404W -
513211N 0033313W -
513138N 0033308W -
513133N 0033411W -
513158N 0033416W -
513207N 0033404W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 343 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.5678111111,51.5352527778,243.84 -3.5710222222,51.5326472222,243.84 -3.569805555599999,51.5257222222,243.84 -3.5522638889,51.52710833329999,243.84 -3.5535388889,51.53633333329999,243.84 -3.5678111111,51.5352527778,243.84 + + + + +
+ + EGRU168 HMP PENTONVILLE + 513256N 0000726W -
513258N 0000659W -
513257N 0000641W -
513231N 0000624W -
513222N 0000721W -
513256N 0000726W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 141 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1238444444,51.54883611109999,182.88 -0.1224222222,51.5393944444,182.88 -0.1066055556,51.54205,182.88 -0.1114833333,51.5491972222,182.88 -0.1164833333,51.5494138889,182.88 -0.1238444444,51.54883611109999,182.88 + + + + +
+ + EGRU169 HMP ROCHESTER + 512226N 0002853E -
512227N 0002947E -
512201N 0003010E -
512147N 0003000E -
512136N 0002947E -
512137N 0002930E -
512226N 0002853E
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Rochester Tower (FRZ - EGRU139A) and HMPPS.
Contact: Rochester Tower 01634-869969 (Option 3 (Air Traffic Control)) Tower@rochesterairport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 326 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4812666667,51.3738055556,243.84 0.4916833333,51.3603027778,243.84 0.4963916667,51.3601055556,243.84 0.5000972222,51.3629972222,243.84 0.5027888889,51.36703333330001,243.84 0.4962694444,51.3742805556,243.84 0.4812666667,51.3738055556,243.84 + + + + +
+ + EGRU170 HMP SEND + 511647N 0002943W -
511649N 0002911W -
511610N 0002857W -
511605N 0002942W -
511620N 0002953W -
511634N 0002958W -
511647N 0002943W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 182 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4953472222,51.2797444444,182.88 -0.4993222222,51.2761944444,182.88 -0.4980666667,51.2721388889,182.88 -0.4950305555999999,51.26801388889999,182.88 -0.4824361111,51.2694277778,182.88 -0.4863444444,51.28026666669999,182.88 -0.4953472222,51.2797444444,182.88 + + + + +
+ + EGRU171 HMP SWALESIDE/ELMLEY + 512358N 0005051E -
512345N 0005148E -
512306N 0005126E -
512259N 0005101E -
512309N 0005025E -
512358N 0005051E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 73 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8475638889,51.3994277778,152.4 0.8404138889,51.3857027778,152.4 0.8501388889,51.3830972222,152.4 0.8572611110999999,51.38499722220001,152.4 0.8634527778,51.3958083333,152.4 0.8475638889,51.3994277778,152.4 + + + + +
+ + EGRU172 HMP SWANSEA + 513706N 0035719W -
513711N 0035655W -
513707N 0035636W -
513647N 0035625W -
513637N 0035706W -
513647N 0035724W -
513706N 0035719W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 27 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9554083333,51.6182055556,152.4 -3.9566,51.61305,152.4 -3.9516,51.6103583333,152.4 -3.9402194444,51.61293055559999,152.4 -3.9434361111,51.61853888889999,152.4 -3.9486805556,51.6196555556,152.4 -3.9554083333,51.6182055556,152.4 + + + + +
+ + EGRU173 HMP THE MOUNT + 514353N 0003231W -
514355N 0003207W -
514340N 0003138W -
514313N 0003213W -
514315N 0003255W -
514332N 0003253W -
514343N 0003245W -
514353N 0003231W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 539 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5418638889,51.73138888890001,304.8 -0.5458194444,51.72863888889999,304.8 -0.54795,51.72567777779999,304.8 -0.5487111111,51.72091111110001,304.8 -0.5369555556,51.7203027778,304.8 -0.5273166667,51.7278194444,304.8 -0.5353611111,51.7318416667,304.8 -0.5418638889,51.73138888890001,304.8 + + + + +
+ + EGRU174 HMP USK + 514218N 0025347W -
514153N 0025327W -
514139N 0025411W -
514205N 0025433W -
514218N 0025347W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 61 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8964611111,51.7049333333,152.4 -2.909075,51.70134166670001,152.4 -2.9031472222,51.6940388889,152.4 -2.8909361111,51.6980722222,152.4 -2.8964611111,51.7049333333,152.4 + + + + +
+ + EGRU175 HMP WANDSWORTH + 512722N 0001030W -
512653N 0001006W -
512636N 0001042W -
512659N 0001111W -
512714N 0001056W -
512722N 0001030W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 112 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1751111111,51.4561361111,182.88 -0.1822138889,51.45391944440001,182.88 -0.1864583333,51.4496,182.88 -0.1783527778,51.4432166667,182.88 -0.1683916667,51.4481388889,182.88 -0.1751111111,51.4561361111,182.88 + + + + +
+ + EGRU176 HMP WINCHESTER + 510400N 0012008W -
510409N 0011927W -
510355N 0011917W -
510334N 0011913W -
510330N 0012001W -
510400N 0012008W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 333 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3355916667,51.0667638889,243.84 -1.3336277778,51.0584444444,243.84 -1.3203583333,51.0595305556,243.84 -1.3214416667,51.06528611109999,243.84 -1.3242,51.0690611111,243.84 -1.3355916667,51.0667638889,243.84 + + + + +
+ + EGRU177 HMP WORMWOOD SCRUBS + 513116N 0001456W -
513119N 0001401W -
513047N 0001352W -
513044N 0001445W -
513057N 0001454W -
513116N 0001456W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 51 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2490222222,51.52105277780001,152.4 -0.2482861111,51.5157277778,152.4 -0.245725,51.51224999999999,152.4 -0.2311805556,51.513125,152.4 -0.2334805556,51.5218972222,152.4 -0.2490222222,51.52105277780001,152.4 + + + + +
+ + EGRU201A WEST WALES/ABERPORTH + A circle, 2 NM radius, centred at 520653N 0043334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5594166667,52.1480051098,609.6 -4.5649804396,52.14782854620001,609.6 -4.5704851043,52.1473007313,609.6 -4.5758721847,52.14642727210001,609.6 -4.5810844621,52.1452174474,609.6 -4.5860665862,52.1436841082,609.6 -4.5907656665,52.1418435403,609.6 -4.595131836,52.13971529059999,609.6 -4.5991187822,52.13732195819999,609.6 -4.6026842393,52.1346889531,609.6 -4.6057904364,52.1318442253,609.6 -4.6084044967,52.1288179668,609.6 -4.610498784,52.1256422898,609.6 -4.6120511927,52.1223508853,609.6 -4.6130453778,52.1189786645,609.6 -4.6134709236,52.11556138790001,609.6 -4.613323449,52.1121352855,609.6 -4.6126046482,52.1087366727,609.6 -4.6113222675,52.10540156540001,609.6 -4.6094900176,52.1021652986,609.6 -4.6071274234,52.0990621525,609.6 -4.6042596129,52.0961249906,609.6 -4.6009170469,52.0933849121,609.6 -4.5971351939,52.090870924,609.6 -4.5929541522,52.08860963539999,609.6 -4.588418225,52.0866249767,609.6 -4.5835754511,52.084937948,609.6 -4.5784770974,52.083566398,609.6 -4.5731771188,52.0825248361,609.6 -4.5677315897,52.0818242799,609.6 -4.5621981139,52.0814721395,609.6 -4.5566352195,52.0814721395,609.6 -4.5511017437,52.0818242799,609.6 -4.5456562145,52.0825248361,609.6 -4.5403562359,52.083566398,609.6 -4.5352578823,52.084937948,609.6 -4.5304151083,52.0866249767,609.6 -4.5258791811,52.08860963539999,609.6 -4.5216981395,52.090870924,609.6 -4.5179162864,52.0933849121,609.6 -4.5145737204,52.0961249906,609.6 -4.5117059099,52.0990621525,609.6 -4.5093433158,52.1021652986,609.6 -4.5075110659,52.10540156540001,609.6 -4.5062286851,52.1087366727,609.6 -4.5055098843,52.1121352855,609.6 -4.5053624097,52.11556138790001,609.6 -4.5057879555,52.1189786645,609.6 -4.5067821406,52.1223508853,609.6 -4.5083345493,52.1256422898,609.6 -4.5104288367,52.1288179668,609.6 -4.513042897,52.1318442253,609.6 -4.516149094,52.1346889531,609.6 -4.5197145511,52.13732195819999,609.6 -4.5237014973,52.13971529059999,609.6 -4.5280676668,52.1418435403,609.6 -4.5327667471,52.1436841082,609.6 -4.5377488713,52.1452174474,609.6 -4.5429611486,52.14642727210001,609.6 -4.548348229,52.1473007313,609.6 -4.5538528938,52.14782854620001,609.6 -4.5594166667,52.1480051098,609.6 + + + + +
+ + EGRU201B WEST WALES/ABERPORTH RWY 07 + 520543N 0043806W -
520614N 0043822W -
520633N 0043646W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to
520602N 0043630W -
520543N 0043806W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6350722222,52.0952472222,609.6 -4.6082841389,52.1004781111,609.6 -4.6101710488,52.1032481534,609.6 -4.6116450046,52.1061116413,609.6 -4.6126939167,52.1090452778,609.6 -4.6394694444,52.1038166667,609.6 -4.6350722222,52.0952472222,609.6 + + + + +
+ + EGRU201C WEST WALES/ABERPORTH RWY 25 + 520803N 0042902W -
520732N 0042846W -
520713N 0043022W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520653N 0043334W to
520744N 0043038W -
520803N 0042902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flights not permitted unless permission has been granted by the aerodrome operator. Information relating to flight within the FRZ and an on-line application form is available on the aerodrome's website http://www.flyuav.co.uk.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4837666667,52.13411944440001,609.6 -4.5105152222,52.12893122220001,609.6 -4.5086338997,52.12615934320001,609.6 -4.5071664244,52.12329435000001,609.6 -4.5061246944,52.1203595833,609.6 -4.4793638889,52.12555,609.6 -4.4837666667,52.13411944440001,609.6 + + + + +
+ + EGRU202A WELSHPOOL + A circle, 2 NM radius, centred at 523743N 0030912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1532972222,52.6619383097,609.6 -3.1589260268,52.66176175910001,609.6 -3.1644950299,52.661233983,609.6 -3.1699450695,52.6603605885,609.6 -3.1752182559,52.6591508538,609.6 -3.1802585903,52.6576176296,609.6 -3.1850125627,52.65577720109999,609.6 -3.1894297226,52.65364911429999,609.6 -3.1934632159,52.6512559674,609.6 -3.1970702834,52.6486231691,609.6 -3.2002127138,52.64577866800001,609.6 -3.2028572478,52.6427526543,609.6 -3.2049759285,52.6395772385,609.6 -3.2065463945,52.6362861091,609.6 -3.2075521128,52.6329141749,609.6 -3.2079825492,52.6294971935,609.6 -3.2078332746,52.6260713921,609.6 -3.2071060066,52.6226730826,609.6 -3.2058085849,52.6193382778,609.6 -3.2039548833,52.61610230880001,609.6 -3.2015646572,52.6129994526,609.6 -3.1986633301,52.61006256870001,609.6 -3.1952817199,52.6073227528,609.6 -3.19145571,52.6048090084,609.6 -3.1872258673,52.60254794120001,609.6 -3.1826370117,52.6005634786,609.6 -3.1777377416,52.5988766179,609.6 -3.1725799209,52.59750520539999,609.6 -3.167218132,52.59646374839999,609.6 -3.1617091013,52.595763263,609.6 -3.156111102,52.5954111583,609.6 -3.1504833424,52.5954111583,609.6 -3.1448853432,52.595763263,609.6 -3.1393763124,52.59646374839999,609.6 -3.1340145236,52.59750520539999,609.6 -3.1288567029,52.5988766179,609.6 -3.1239574328,52.6005634786,609.6 -3.1193685771,52.60254794120001,609.6 -3.1151387345,52.6048090084,609.6 -3.111312724599999,52.6073227528,609.6 -3.1079311144,52.61006256870001,609.6 -3.1050297872,52.6129994526,609.6 -3.102639561200001,52.61610230880001,609.6 -3.1007858596,52.6193382778,609.6 -3.0994884379,52.6226730826,609.6 -3.0987611698,52.6260713921,609.6 -3.0986118953,52.6294971935,609.6 -3.0990423317,52.6329141749,609.6 -3.1000480499,52.6362861091,609.6 -3.1016185159,52.6395772385,609.6 -3.1037371966,52.6427526543,609.6 -3.1063817306,52.64577866800001,609.6 -3.109524161,52.6486231691,609.6 -3.1131312286,52.6512559674,609.6 -3.1171647219,52.65364911429999,609.6 -3.1215818817,52.65577720109999,609.6 -3.1263358541,52.6576176296,609.6 -3.1313761886,52.6591508538,609.6 -3.136649375,52.6603605885,609.6 -3.1420994145,52.661233983,609.6 -3.1476684176,52.66176175910001,609.6 -3.1532972222,52.6619383097,609.6 + + + + +
+ + EGRU202B WELSHPOOL RWY 04 + 523510N 0031134W -
523529N 0031218W -
523615N 0031125W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to
523556N 0031041W -
523510N 0031134W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1928166667,52.5861333333,609.6 -3.1781366111,52.5989991389,609.6 -3.1824262144,52.6004823189,609.6 -3.186479086,52.6021947615,609.6 -3.19026225,52.6041225556,609.6 -3.2049305556,52.5912638889,609.6 -3.1928166667,52.5861333333,609.6 + + + + +
+ + EGRU202C WELSHPOOL RWY 22 + 524016N 0030650W -
523957N 0030606W -
523911N 0030658W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523743N 0030912W to
523930N 0030742W -
524016N 0030650W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1138,52.67099999999999,609.6 -3.1283630833,52.65828202780001,609.6 -3.1240726758,52.6567936288,609.6 -3.1200207057,52.6550759558,609.6 -3.1162401944,52.6531430278,609.6 -3.1016638889,52.6658694444,609.6 -3.1138,52.67099999999999,609.6 + + + + +
+ + EGRU203A SHOBDON + A circle, 2 NM radius, centred at 521430N 0025252W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8811111111,52.2749543894,609.6 -2.8866907656,52.274777829,609.6 -2.892211142599999,52.27425002369999,609.6 -2.8976135985,52.2733765806,609.6 -2.9028407506,52.2721667782,609.6 -2.9078370904,52.2706334675,609.6 -2.9125495762,52.2687929342,609.6 -2.9169281982,52.26666472489999,609.6 -2.9209265119,52.2642714384,609.6 -2.9245021309,52.2616384845,609.6 -2.9276171767,52.2587938129,609.6 -2.9302386792,52.255767615,609.6 -2.9323389239,52.2525920027,609.6 -2.9338957425,52.2493006663,609.6 -2.9348927443,52.2459285165,609.6 -2.9353194846,52.2425113129,609.6 -2.935171570500001,52.23908528490001,609.6 -2.934450702,52.23568674720001,609.6 -2.9331646481,52.2323517147,609.6 -2.9313271595,52.2291155216,609.6 -2.9289578173,52.2260124472,609.6 -2.9260818216,52.22307535400001,609.6 -2.9227297205,52.2203353404,609.6 -2.918937083699999,52.2178214126,609.6 -2.9147441241,52.2155601787,609.6 -2.910195271,52.2135755685,609.6 -2.9053386998,52.2118885813,609.6 -2.9002258233,52.2105170653,609.6 -2.8949107497,52.2094755293,609.6 -2.8894497124,52.20877499060001,609.6 -2.8839004789,52.208422859,609.6 -2.8783217433,52.208422859,609.6 -2.872772509899999,52.20877499060001,609.6 -2.8673114726,52.2094755293,609.6 -2.8619963989,52.2105170653,609.6 -2.8568835225,52.2118885813,609.6 -2.8520269513,52.2135755685,609.6 -2.847478098099999,52.2155601787,609.6 -2.8432851385,52.2178214126,609.6 -2.8394925017,52.2203353404,609.6 -2.8361404006,52.22307535400001,609.6 -2.8332644049,52.2260124472,609.6 -2.8308950627,52.2291155216,609.6 -2.8290575741,52.2323517147,609.6 -2.8277715202,52.23568674720001,609.6 -2.8270506517,52.23908528490001,609.6 -2.826902737600001,52.2425113129,609.6 -2.827329477900001,52.2459285165,609.6 -2.8283264797,52.2493006663,609.6 -2.8298832984,52.2525920027,609.6 -2.831983543,52.255767615,609.6 -2.8346050455,52.2587938129,609.6 -2.8377200913,52.2616384845,609.6 -2.8412957103,52.2642714384,609.6 -2.845294024,52.26666472489999,609.6 -2.8496726461,52.2687929342,609.6 -2.8543851318,52.2706334675,609.6 -2.8593814716,52.2721667782,609.6 -2.8646086238,52.2733765806,609.6 -2.8700110796,52.27425002369999,609.6 -2.875531456600001,52.274777829,609.6 -2.8811111111,52.2749543894,609.6 + + + + +
+ + EGRU203B SHOBDON RWY 08 + 521352N 0025732W -
521424N 0025739W -
521431N 0025607W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to
521359N 0025600W -
521352N 0025732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9589777778,52.2310055556,609.6 -2.9334707778,52.2330216667,609.6 -2.9345288123,52.23595499950001,609.6 -2.9351518764,52.2389349498,609.6 -2.935334805600001,52.24193724999999,609.6 -2.9608333333,52.2399222222,609.6 -2.9589777778,52.2310055556,609.6 + + + + +
+ + EGRU203C SHOBDON RWY 26 + 521508N 0024813W -
521436N 0024806W -
521429N 0024937W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521430N 0025252W to
521501N 0024943W -
521508N 0024813W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.803475,52.2522666667,609.6 -2.828736000000001,52.2502995833,609.6 -2.8276831046,52.2473661174,609.6 -2.8270654286,52.2443863328,609.6 -2.8268879167,52.2413845,609.6 -2.8016166667,52.2433527778,609.6 -2.803475,52.2522666667,609.6 + + + + +
+ + EGRU204A SLEAP + A circle, 2 NM radius, centred at 525002N 0024618W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7716666667,52.8671732622,609.6 -2.7773219972,52.8669967167,609.6 -2.7829172434,52.86646895609999,609.6 -2.7883929636,52.8655955872,609.6 -2.7936909943,52.86438588819999,609.6 -2.7987550722,52.8628527096,609.6 -2.8035314345,52.8610123364,609.6 -2.8079693927,52.8588843143,609.6 -2.8120218721,52.8564912409,609.6 -2.815645911899999,52.8538585248,609.6 -2.8188031213,52.8510141137,609.6 -2.8214600849,52.8479881974,609.6 -2.8235887151,52.8448128853,609.6 -2.8251665461,52.84152186539999,609.6 -2.8261769682,52.8381500451,609.6 -2.8266093991,52.83473318120001,609.6 -2.82645939,52.8313074995,609.6 -2.8257286679,52.8279093109,609.6 -2.8244251109,52.8245746265,609.6 -2.8225626591,52.8213387762,609.6 -2.8201611621,52.81823603550001,609.6 -2.8172461638,52.8152992624,609.6 -2.8138486278,52.8125595511,609.6 -2.8100046069,52.8100459039,609.6 -2.805754859,52.807784925,609.6 -2.8011444147,52.80580054070001,609.6 -2.7962221007,52.8041137471,609.6 -2.7910400244,52.8027423894,609.6 -2.7856530242,52.8017009742,609.6 -2.7801180923,52.8010005171,609.6 -2.7744937751,52.80064842670001,609.6 -2.7688395582,52.80064842670001,609.6 -2.763215241,52.8010005171,609.6 -2.7576803091,52.8017009742,609.6 -2.7522933089,52.8027423894,609.6 -2.7471112326,52.8041137471,609.6 -2.7421889187,52.80580054070001,609.6 -2.7375784743,52.807784925,609.6 -2.7333287264,52.8100459039,609.6 -2.7294847055,52.8125595511,609.6 -2.7260871695,52.8152992624,609.6 -2.7231721712,52.81823603550001,609.6 -2.7207706742,52.8213387762,609.6 -2.7189082225,52.8245746265,609.6 -2.7176046654,52.8279093109,609.6 -2.7168739433,52.8313074995,609.6 -2.7167239343,52.83473318120001,609.6 -2.7171563651,52.8381500451,609.6 -2.7181667872,52.84152186539999,609.6 -2.7197446182,52.8448128853,609.6 -2.7218732484,52.8479881974,609.6 -2.7245302121,52.8510141137,609.6 -2.7276874215,52.8538585248,609.6 -2.7313114613,52.8564912409,609.6 -2.7353639406,52.8588843143,609.6 -2.7398018988,52.8610123364,609.6 -2.7445782612,52.8628527096,609.6 -2.7496423391,52.86438588819999,609.6 -2.7549403698,52.8655955872,609.6 -2.7604160899,52.86646895609999,609.6 -2.7660113361,52.8669967167,609.6 -2.7716666667,52.8671732622,609.6 + + + + +
+ + EGRU204B SLEAP RWY 05 + 524748N 0024923W -
524811N 0025001W -
524850N 0024856W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
524827N 0024818W -
524748N 0024923W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.823030555599999,52.796675,609.6 -2.8051105556,52.80748088890001,609.6 -2.8089038559,52.8094142415,609.6 -2.8123944447,52.81154682439999,609.6 -2.815553888899999,52.8138613056,609.6 -2.8334805556,52.80305,609.6 -2.823030555599999,52.796675,609.6 + + + + +
+ + EGRU204C SLEAP RWY 23 + 525217N 0024311W -
525154N 0024234W -
525114N 0024340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
525137N 0024418W -
525217N 0024311W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7198416667,52.8714472222,609.6 -2.7383165278,52.86034961109999,609.6 -2.7345122636,52.8584212007,609.6 -2.7310110402,52.8562929696,609.6 -2.7278413611,52.8539822778,609.6 -2.7093722222,52.865075,609.6 -2.7198416667,52.8714472222,609.6 + + + + +
+ + EGRU204D SLEAP RWY 18 + 525253N 0024646W -
525253N 0024553W -
525201N 0024551W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
525201N 0024644W -
525253N 0024646W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7795583333,52.88128333329999,609.6 -2.7789823611,52.8668773056,609.6 -2.7740367547,52.8671423114,609.6 -2.7690717949,52.8671361609,609.6 -2.7641280278,52.8668588889,609.6 -2.7647083333,52.8815,609.6 -2.7795583333,52.88128333329999,609.6 + + + + +
+ + EGRU204E SLEAP RWY 36 + 524705N 0024539W -
524704N 0024633W -
524803N 0024635W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525002N 0024618W to
524804N 0024542W -
524705N 0024539W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7608805556,52.7847416667,609.6 -2.7615295,52.8011758333,609.6 -2.7664380394,52.8007554016,609.6 -2.7713890858,52.80060474379999,609.6 -2.7763423889,52.8007250833,609.6 -2.7756972222,52.7845277778,609.6 -2.7608805556,52.7847416667,609.6 + + + + +
+ + EGRU205A SHAWBURY + A circle, 2 NM radius, centred at 524737N 0024005W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6679388889,52.8269096004,609.6 -2.67358899,52.8267330539,609.6 -2.6791790626,52.8262052903,609.6 -2.6846497199,52.8253319163,609.6 -2.6899428528,52.8241222104,609.6 -2.6950022498,52.8225890229,609.6 -2.6997741981,52.82074863879999,609.6 -2.7042080561,52.818620604,609.6 -2.7082567924,52.8162275163,609.6 -2.7118774863,52.81359478400001,609.6 -2.7150317821,52.8107503553,609.6 -2.7176862954,52.80772441989999,609.6 -2.7198129641,52.80454908750001,609.6 -2.7213893431,52.8012580461,609.6 -2.7223988379,52.7978862036,609.6 -2.7228308756,52.7944693166,609.6 -2.7226810114,52.7910436115,609.6 -2.7219509703,52.7876453991,609.6 -2.7206486227,52.7843106911,609.6 -2.718787896,52.7810748176,609.6 -2.716388621,52.7779720542,609.6 -2.7134763179,52.7750352593,609.6 -2.7100819216,52.7722955276,609.6 -2.7062414514,52.7697818613,609.6 -2.7019956277,52.7675208651,609.6 -2.6973894394,52.7655364654,609.6 -2.6924716684,52.7638496586,609.6 -2.6872943739,52.76247829019999,609.6 -2.6819123439,52.7614368668,609.6 -2.6763825182,52.76073640420001,609.6 -2.6707633894,52.7603843109,609.6 -2.6651143884,52.7603843109,609.6 -2.6594952596,52.76073640420001,609.6 -2.6539654339,52.7614368668,609.6 -2.6485834039,52.76247829019999,609.6 -2.6434061094,52.7638496586,609.6 -2.6384883384,52.7655364654,609.6 -2.6338821501,52.7675208651,609.6 -2.6296363263,52.7697818613,609.6 -2.6257958562,52.7722955276,609.6 -2.6224014599,52.7750352593,609.6 -2.6194891568,52.7779720542,609.6 -2.6170898818,52.7810748176,609.6 -2.615229155,52.7843106911,609.6 -2.6139268075,52.7876453991,609.6 -2.6131967664,52.7910436115,609.6 -2.6130469022,52.7944693166,609.6 -2.6134789398,52.7978862036,609.6 -2.6144884347,52.8012580461,609.6 -2.6160648137,52.80454908750001,609.6 -2.6181914824,52.80772441989999,609.6 -2.6208459957,52.8107503553,609.6 -2.6240002915,52.81359478400001,609.6 -2.6276209853,52.8162275163,609.6 -2.6316697217,52.818620604,609.6 -2.6361035797,52.82074863879999,609.6 -2.640875528,52.8225890229,609.6 -2.645934925,52.8241222104,609.6 -2.6512280578,52.8253319163,609.6 -2.6566987152,52.8262052903,609.6 -2.6622887877,52.8267330539,609.6 -2.6679388889,52.8269096004,609.6 + + + + +
+ + EGRU205B SHAWBURY RWY 05 + 524527N 0024325W -
524550N 0024403W -
524633N 0024252W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524609N 0024218W -
524527N 0024325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7235820278,52.7576245833,609.6 -2.7049352778,52.76903544439999,609.6 -2.7084554449,52.7711671052,609.6 -2.7116432321,52.7734832474,609.6 -2.7144724444,52.7759648611,609.6 -2.7340958611,52.7639548056,609.6 -2.7235820278,52.7576245833,609.6 + + + + +
+ + EGRU205C SHAWBURY RWY 23 + 525011N 0023655W -
524949N 0023617W -
524858N 0023740W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524919N 0023821W -
525011N 0023655W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6153044722,52.8365074722,609.6 -2.6391511389,52.82197188890001,609.6 -2.6350330637,52.82027527139999,609.6 -2.631185824,52.8183596115,609.6 -2.6276410556,52.8162406667,609.6 -2.6047731389,52.8301773333,609.6 -2.6153044722,52.8365074722,609.6 + + + + +
+ + EGRU205D SHAWBURY RWY 18 + 525048N 0024032W -
525048N 0023939W -
524936N 0023938W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524936N 0024032W -
525048N 0024032W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6755396111,52.84677375,609.6 -2.6754679167,52.8265954444,609.6 -2.6705304301,52.826872528,609.6 -2.6655717917,52.8268786728,609.6 -2.6606324722,52.8266138333,609.6 -2.6606972778,52.8467921389,609.6 -2.6755396111,52.84677375,609.6 + + + + +
+ + EGRU205E SHAWBURY RWY 36 + 524426N 0023937W -
524426N 0024031W -
524538N 0024031W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524737N 0024005W to
524538N 0023938W -
524426N 0023937W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6603565556,52.7404752778,609.6 -2.6604210833,52.7606538889,609.6 -2.6653511557,52.76037723659999,609.6 -2.6703022476,52.76037109369999,609.6 -2.6752341389,52.76063552779999,609.6 -2.6751627778,52.7404568889,609.6 -2.6603565556,52.7404752778,609.6 + + + + +
+ + EGRU206A TERNHILL + A circle, 2 NM radius, centred at 525223N 0023156W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5321916667,52.90644526289999,609.6 -2.5378521099,52.90626871849999,609.6 -2.5434524143,52.9057409608,609.6 -2.5489330842,52.9048675968,609.6 -2.5542359034,52.9036579047,609.6 -2.5593045577,52.9021247347,609.6 -2.5640852355,52.9002843721,609.6 -2.5685272025,52.8981563623,609.6 -2.5725833412,52.895763303,609.6 -2.5762106523,52.89313060250001,609.6 -2.5793707102,52.8902862087,609.6 -2.5820300695,52.8872603109,609.6 -2.5841606174,52.8840850187,609.6 -2.5857398679,52.8807940196,609.6 -2.5867511966,52.8774222212,609.6 -2.5871840119,52.8740053798,609.6 -2.5870338612,52.87057972099999,609.6 -2.5863024734,52.8671815554,609.6 -2.5849977337,52.86384689400001,609.6 -2.5831335954,52.86061106649999,609.6 -2.5807299261,52.8575083478,609.6 -2.5778122927,52.8545715958,609.6 -2.5744116872,52.8518319046,609.6 -2.5705641948,52.849318276,609.6 -2.5663106103,52.847057314,609.6 -2.5616960049,52.8450729446,609.6 -2.5567692495,52.8433861638,609.6 -2.5515824981,52.8420148166,609.6 -2.5461906387,52.84097340949999,609.6 -2.5406507145,52.8402729578,609.6 -2.5350213248,52.8399208701,609.6 -2.5293620085,52.8399208701,609.6 -2.5237326188,52.8402729578,609.6 -2.5181926947,52.84097340949999,609.6 -2.5128008352,52.8420148166,609.6 -2.5076140839,52.8433861638,609.6 -2.5026873284,52.8450729446,609.6 -2.498072723,52.847057314,609.6 -2.4938191385,52.849318276,609.6 -2.4899716461,52.8518319046,609.6 -2.4865710406,52.8545715958,609.6 -2.4836534073,52.8575083478,609.6 -2.4812497379,52.86061106649999,609.6 -2.4793855996,52.86384689400001,609.6 -2.47808086,52.8671815554,609.6 -2.4773494721,52.87057972099999,609.6 -2.4771993215,52.8740053798,609.6 -2.4776321367,52.8774222212,609.6 -2.4786434655,52.8807940196,609.6 -2.480222716,52.8840850187,609.6 -2.4823532638,52.8872603109,609.6 -2.4850126232,52.8902862087,609.6 -2.4881726811,52.89313060250001,609.6 -2.4917999922,52.895763303,609.6 -2.4958561309,52.8981563623,609.6 -2.5002980978,52.9002843721,609.6 -2.5050787756,52.9021247347,609.6 -2.5101474299,52.9036579047,609.6 -2.5154502492,52.9048675968,609.6 -2.520930919,52.9057409608,609.6 -2.5265312234,52.90626871849999,609.6 -2.5321916667,52.90644526289999,609.6 + + + + +
+ + EGRU206B TERNHILL RWY 04 + 525004N 0023450W -
525026N 0023529W -
525107N 0023428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525045N 0023348W -
525004N 0023450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5805501389,52.8343893333,609.6 -2.5634260556,52.8457666667,609.6 -2.5673785486,52.847581813,609.6 -2.5710450266,52.8496051651,609.6 -2.5743956389,52.8518202778,609.6 -2.5915122222,52.8404460278,609.6 -2.5805501389,52.8343893333,609.6 + + + + +
+ + EGRU206C TERNHILL RWY 22 + 525443N 0022902W -
525421N 0022822W -
525340N 0022924W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525402N 0023003W -
525443N 0022902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4837607222,52.9119084722,609.6 -2.5009221944,52.900549,609.6 -2.4969673837,52.89873187969999,609.6 -2.4932998953,52.8967064683,609.6 -2.4899496111,52.89448927780001,609.6 -2.4727806111,52.9058518611,609.6 -2.4837607222,52.9119084722,609.6 + + + + +
+ + EGRU206D TERNHILL RWY 10 + 525233N 0023651W -
525305N 0023643W -
525256N 0023506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525224N 0023514W -
525233N 0023651W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6141188611,52.8759196389,609.6 -2.5872000556,52.87338677779999,609.6 -2.5869443115,52.876386522,609.6 -2.5862425569,52.87936009700001,609.6 -2.5851004167,52.88228327779999,609.6 -2.6118228056,52.8847976389,609.6 -2.6141188611,52.8759196389,609.6 + + + + +
+ + EGRU206E TERNHILL RWY 28 + 525212N 0022717W -
525140N 0022725W -
525148N 0022847W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525219N 0022838W -
525212N 0022717W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4546785556,52.8699211389,609.6 -2.4772125278,52.8720677778,609.6 -2.4776011819,52.8690732605,609.6 -2.4784342929,52.8661121323,609.6 -2.479705,52.8632085,609.6 -2.4569738333,52.8610431111,609.6 -2.4546785556,52.8699211389,609.6 + + + + +
+ + EGRU206F TERNHILL RWY 17 + 525513N 0023310W -
525520N 0023217W -
525423N 0023159W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525418N 0023252W -
525513N 0023310W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5527453056,52.9203575,609.6 -2.547651,52.90510488889999,609.6 -2.5428192861,52.9058186705,609.6 -2.5379006231,52.90626566900001,609.6 -2.53293525,52.90644222219999,609.6 -2.5381707222,52.92213338890001,609.6 -2.5527453056,52.9203575,609.6 + + + + +
+ + EGRU206G TERNHILL RWY 35 + 524937N 0023023W -
524931N 0023116W -
525024N 0023134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525223N 0023156W to
525032N 0023042W -
524937N 0023023W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.50649125,52.8270092778,609.6 -2.5115754722,52.8423044722,609.6 -2.5162593978,52.84130443,609.6 -2.5210730991,52.84056426330001,609.6 -2.5259773611,52.84009,609.6 -2.521034,52.8252333889,609.6 -2.50649125,52.8270092778,609.6 + + + + +
+ + EGRU207A COSFORD + A circle, 2 NM radius, centred at 523826N 0021819W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3052,52.6737854649,609.6 -2.3108303271,52.6736089147,609.6 -2.3164008364,52.6730811395,609.6 -2.3218523499,52.67220774639999,609.6 -2.3271269622,52.6709980139,609.6 -2.3321686594,52.6694647923,609.6 -2.3369239169,52.6676243669,609.6 -2.3413422704,52.6654962839,609.6 -2.3453768535,52.66310314119999,609.6 -2.3489848951,52.6604703477,609.6 -2.3521281738,52.6576258518,609.6 -2.3547734212,52.65459984369999,609.6 -2.356892673,52.6514244339,609.6 -2.3584635616,52.6481333109,609.6 -2.3594695499,52.64476138319999,609.6 -2.3599001008,52.6413444087,609.6 -2.3597507841,52.6379186141,609.6 -2.3590233178,52.63452031169999,609.6 -2.3577255439,52.6311855137,609.6 -2.3558713401,52.6279495517,609.6 -2.3534804672,52.6248467021,609.6 -2.3505783554,52.6219098246,609.6 -2.3471958311,52.6191700147,609.6 -2.3433687875,52.6166562759,609.6 -2.3391378023,52.61439521379999,609.6 -2.3345477076,52.6124107558,609.6 -2.3296471149,52.610723899,609.6 -2.3244879021,52.6093524896,609.6 -2.3191246662,52.608311035,609.6 -2.3136141488,52.60761055130001,609.6 -2.3080146391,52.6072584474,609.6 -2.3023853609,52.6072584474,609.6 -2.2967858512,52.60761055130001,609.6 -2.2912753338,52.608311035,609.6 -2.2859120979,52.6093524896,609.6 -2.2807528851,52.610723899,609.6 -2.2758522924,52.6124107558,609.6 -2.2712621977,52.61439521379999,609.6 -2.2670312125,52.6166562759,609.6 -2.2632041689,52.6191700147,609.6 -2.2598216446,52.6219098246,609.6 -2.2569195328,52.6248467021,609.6 -2.2545286599,52.6279495517,609.6 -2.2526744561,52.6311855137,609.6 -2.2513766822,52.63452031169999,609.6 -2.2506492159,52.6379186141,609.6 -2.2504998992,52.6413444087,609.6 -2.2509304501,52.64476138319999,609.6 -2.2519364384,52.6481333109,609.6 -2.253507327,52.6514244339,609.6 -2.2556265788,52.65459984369999,609.6 -2.2582718262,52.6576258518,609.6 -2.2614151049,52.6604703477,609.6 -2.2650231465,52.66310314119999,609.6 -2.2690577296,52.6654962839,609.6 -2.2734760831,52.6676243669,609.6 -2.2782313406,52.6694647923,609.6 -2.2832730378,52.6709980139,609.6 -2.2885476501,52.67220774639999,609.6 -2.2939991636,52.6730811395,609.6 -2.2995696729,52.6736089147,609.6 -2.3052,52.6737854649,609.6 + + + + +
+ + EGRU207B COSFORD RWY 06 + 523637N 0022215W -
523704N 0022243W -
523737N 0022118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523709N 0022050W -
523637N 0022215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3708121389,52.6102927222,609.6 -2.3473025278,52.619248,609.6 -2.3502802235,52.6216433353,609.6 -2.3528913183,52.62419221599999,609.6 -2.3551145,52.62687391669999,609.6 -2.3786348056,52.6179139722,609.6 -2.3708121389,52.6102927222,609.6 + + + + +
+ + EGRU207C COSFORD RWY 24 + 524015N 0021423W -
523947N 0021355W -
523915N 0021519W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523943N 0021547W -
524015N 0021423W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2396455556,52.6707405556,609.6 -2.26317,52.6618198889,609.6 -2.2601815668,52.6594282563,609.6 -2.2575601865,52.65688249580001,609.6 -2.2553271667,52.6542033611,609.6 -2.2318134444,52.6631193889,609.6 -2.2396455556,52.6707405556,609.6 + + + + +
+ + EGRU207D COSFORD RWY 06L + 523639N 0022217W -
523707N 0022245W -
523739N 0022120W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523711N 0022053W -
523639N 0022217W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3714746389,52.6108995278,609.6 -2.3480534722,52.6198109722,609.6 -2.3509455268,52.6222458531,609.6 -2.3534653466,52.6248294636,609.6 -2.3555923611,52.62754077779999,609.6 -2.3792911389,52.6185231667,609.6 -2.3714746389,52.6108995278,609.6 + + + + +
+ + EGRU207E COSFORD RWY 24R + 524016N 0021428W -
523948N 0021359W -
523917N 0021521W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523826N 0021819W to
523944N 0021550W -
524016N 0021428W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2410140556,52.67101977780001,609.6 -2.2639089722,52.6623476389,609.6 -2.260838454,52.6599937279,609.6 -2.2581298286,52.6574809994,609.6 -2.2558051389,52.6548299444,609.6 -2.2331881944,52.6633962222,609.6 -2.2410140556,52.67101977780001,609.6 + + + + +
+ + EGRU208A WOLVERHAMPTON/HALFPENNY GREEN + A circle, 2 NM radius, centred at 523103N 0021534W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2595472222,52.5506694943,609.6 -2.2651617798,52.550492941,609.6 -2.2707166877,52.54996515649999,609.6 -2.2761529343,52.549091748,609.6 -2.2814127768,52.54788199399999,609.6 -2.2864403587,52.5463487449,609.6 -2.2911823054,52.5445082863,609.6 -2.2955882944,52.5423801644,609.6 -2.2996115904,52.5399869775,609.6 -2.303209542,52.5373541345,609.6 -2.3063440346,52.5345095845,609.6 -2.3089818926,52.53148351789999,609.6 -2.3110952293,52.52830804570001,609.6 -2.3126617395,52.5250168569,609.6 -2.3136649312,52.5216448608,609.6 -2.3140942963,52.51822781570001,609.6 -2.3139454162,52.5148019491,609.6 -2.3132200032,52.5114035741,609.6 -2.3119258767,52.50806870390001,609.6 -2.3100768748,52.5048326706,609.6 -2.3076927023,52.5017297516,609.6 -2.3047987179,52.4987928076,609.6 -2.3014256614,52.4960529349,609.6 -2.2976093253,52.4935391378,609.6 -2.2933901738,52.49127802269999,609.6 -2.2888129135,52.4892935177,609.6 -2.2839260204,52.4876066206,609.6 -2.2787812274,52.48623517840001,609.6 -2.2734329797,52.4851936987,609.6 -2.2679378606,52.484493198,609.6 -2.2623539968,52.4841410855,609.6 -2.2567404476,52.4841410855,609.6 -2.2511565839,52.484493198,609.6 -2.2456614647,52.4851936987,609.6 -2.240313217,52.48623517840001,609.6 -2.2351684241,52.4876066206,609.6 -2.2302815309,52.4892935177,609.6 -2.2257042707,52.49127802269999,609.6 -2.2214851191,52.4935391378,609.6 -2.217668783,52.4960529349,609.6 -2.2142957265,52.4987928076,609.6 -2.2114017421,52.5017297516,609.6 -2.2090175697,52.5048326706,609.6 -2.2071685677,52.50806870390001,609.6 -2.2058744412,52.5114035741,609.6 -2.2051490283,52.5148019491,609.6 -2.2050001482,52.51822781570001,609.6 -2.2054295133,52.5216448608,609.6 -2.206432705,52.5250168569,609.6 -2.2079992151,52.52830804570001,609.6 -2.2101125519,52.53148351789999,609.6 -2.2127504099,52.5345095845,609.6 -2.2158849024,52.5373541345,609.6 -2.2194828541,52.5399869775,609.6 -2.22350615,52.5423801644,609.6 -2.227912139,52.5445082863,609.6 -2.2326540858,52.5463487449,609.6 -2.2376816676,52.54788199399999,609.6 -2.2429415102,52.549091748,609.6 -2.2483777568,52.54996515649999,609.6 -2.2539326647,52.550492941,609.6 -2.2595472222,52.5506694943,609.6 + + + + +
+ + EGRU208B WOLVERHAMPTON/HALFPENNY GREEN RWY 04 + 522840N 0021816W -
522859N 0021859W -
522945N 0021803W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
522923N 0021724W -
522840N 0021816W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3045555556,52.4777166667,609.6 -2.2899011667,52.4897268611,609.6 -2.2938762625,52.49151540919999,609.6 -2.2975703338,52.4935160039,609.6 -2.3009530833,52.4957122778,609.6 -2.3163527778,52.4830888889,609.6 -2.3045555556,52.4777166667,609.6 + + + + +
+ + EGRU208C WOLVERHAMPTON/HALFPENNY GREEN RWY 22 + 523332N 0021326W -
523313N 0021243W -
523235N 0021329W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
523252N 0021414W -
523332N 0021326W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2237694444,52.5588416667,609.6 -2.2373114444,52.5477822778,609.6 -2.2328922036,52.5464304954,609.6 -2.2286919692,52.54484039,609.6 -2.2247452222,52.5430250278,609.6 -2.21195,52.55347222220001,609.6 -2.2237694444,52.5588416667,609.6 + + + + +
+ + EGRU208D WOLVERHAMPTON/HALFPENNY GREEN RWY 16 + 523335N 0021755W -
523348N 0021707W -
523258N 0021630W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
523244N 0021718W -
523335N 0021755W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2987055556,52.5595916667,609.6 -2.2884155278,52.54563275,609.6 -2.2841209325,52.5471052761,609.6 -2.2796258124,52.5483356141,609.6 -2.2749668333,52.54931372219999,609.6 -2.28525,52.5632694444,609.6 -2.2987055556,52.5595916667,609.6 + + + + +
+ + EGRU208E WOLVERHAMPTON/HALFPENNY GREEN RWY 34 + 522830N 0021313W -
522816N 0021401W -
522908N 0021439W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523103N 0021534W to
522921N 0021351W -
522830N 0021313W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2202611111,52.4749055556,609.6 -2.2307041944,52.4891311944,609.6 -2.2349940211,52.4876600186,609.6 -2.2394833707,52.48643072530001,609.6 -2.24413575,52.48545330559999,609.6 -2.2336861111,52.471225,609.6 -2.2202611111,52.4749055556,609.6 + + + + +
+ + EGRU209A TATENHILL + A circle, 2 NM radius, centred at 524851N 0014553W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7647083333,52.84735392950001,609.6 -1.7703610882,52.8471773836,609.6 -1.7759537862,52.8466496214,609.6 -1.7814270127,52.8457762501,609.6 -1.786722631,52.8445665477,609.6 -1.7917844034,52.8430333647,609.6 -1.7965585917,52.8411929861,609.6 -1.8009945304,52.8390649577,609.6 -1.8050451662,52.8366718773,609.6 -1.808667558,52.8340391532,609.6 -1.8118233323,52.8311947335,609.6 -1.8144790891,52.8281688078,609.6 -1.8166067531,52.82499348569999,609.6 -1.818183869,52.8217024552,609.6 -1.8191938344,52.818330624,609.6 -1.8196260716,52.81491374880001,609.6 -1.8194761339,52.8114880555,609.6 -1.8187457472,52.8080898552,609.6 -1.8174427859,52.8047551592,609.6 -1.8155811838,52.8015192975,609.6 -1.8131807812,52.7984165455,609.6 -1.8102671103,52.79547976170001,609.6 -1.8068711208,52.7927400404,609.6 -1.8030288488,52.7902263838,609.6 -1.7987810336,52.7879653964,609.6 -1.7941726856,52.78598100450001,609.6 -1.7892526091,52.7842942044,609.6 -1.7840728881,52.7829228414,609.6 -1.7786883359,52.7818814222,609.6 -1.773155919,52.7811809624,609.6 -1.7675341573,52.7808288706,609.6 -1.7618825094,52.7808288706,609.6 -1.7562607477,52.7811809624,609.6 -1.7507283308,52.7818814222,609.6 -1.7453437786,52.7829228414,609.6 -1.7401640575,52.7842942044,609.6 -1.7352439811,52.78598100450001,609.6 -1.730635633,52.7879653964,609.6 -1.7263878179,52.7902263838,609.6 -1.7225455459,52.7927400404,609.6 -1.7191495563,52.79547976170001,609.6 -1.7162358855,52.7984165455,609.6 -1.7138354829,52.8015192975,609.6 -1.7119738808,52.8047551592,609.6 -1.7106709195,52.8080898552,609.6 -1.7099405328,52.8114880555,609.6 -1.7097905951,52.81491374880001,609.6 -1.7102228322,52.818330624,609.6 -1.7112327977,52.8217024552,609.6 -1.7128099135,52.82499348569999,609.6 -1.7149375776,52.8281688078,609.6 -1.7175933343,52.8311947335,609.6 -1.7207491087,52.8340391532,609.6 -1.7243715005,52.8366718773,609.6 -1.7284221363,52.8390649577,609.6 -1.7328580749,52.8411929861,609.6 -1.7376322632,52.8430333647,609.6 -1.7426940356,52.8445665477,609.6 -1.7479896539,52.8457762501,609.6 -1.7534628805,52.8466496214,609.6 -1.7590555784,52.8471773836,609.6 -1.7647083333,52.84735392950001,609.6 + + + + +
+ + EGRU209B TATENHILL RWY 08 + 524744N 0015032W -
524815N 0015047W -
524833N 0014908W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to
524802N 0014853W -
524744N 0015032W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8422166667,52.7956138889,609.6 -1.8148514167,52.8004843611,609.6 -1.8166692181,52.80327779060001,609.6 -1.8180644306,52.80615912030001,609.6 -1.8190256111,52.80910491669999,609.6 -1.8463805556,52.80423611110001,609.6 -1.8422166667,52.7956138889,609.6 + + + + +
+ + EGRU209C TATENHILL RWY 26 + 524957N 0014114W -
524926N 0014059W -
524908N 0014237W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524851N 0014553W to
524939N 0014252W -
524957N 0014114W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6871555556,52.8324722222,609.6 -1.7145350278,52.8276346944,609.6 -1.7127224882,52.8248396575,609.6 -1.7113333994,52.8219570266,609.6 -1.710379,52.8190102778,609.6 -1.6829861111,52.82384999999999,609.6 -1.6871555556,52.8324722222,609.6 + + + + +
+ + EGRU210A BIRMINGHAM + A circle, 2.5 NM radius, centred at 522722N 0014502W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7505555556,52.4977192163,609.6 -1.7568458982,52.497541557,609.6 -1.763082423,52.4970100989,609.6 -1.7692117761,52.496129389,609.6 -1.7751815286,52.49490696149999,609.6 -1.7809406276,52.4933532735,609.6 -1.7864398366,52.4914816145,609.6 -1.7916321586,52.48930799189999,609.6 -1.7964732401,52.4868509931,609.6 -1.8009217512,52.4841316255,609.6 -1.8049397389,52.4811731357,609.6 -1.8084929515,52.4780008096,609.6 -1.8115511291,52.4746417551,609.6 -1.8140882605,52.4711246695,609.6 -1.8160828021,52.467479593,609.6 -1.8175178582,52.4637376518,609.6 -1.8183813209,52.4599307911,609.6 -1.818665969,52.4560915023,609.6 -1.8183695247,52.4522525448,609.6 -1.8174946675,52.448446667,609.6 -1.8160490067,52.44470632659999,609.6 -1.8140450112,52.4410634144,609.6 -1.8114998987,52.4375489828,609.6 -1.8084354845,52.4341929817,609.6 -1.8048779924,52.4310240045,609.6 -1.8008578279,52.4280690449,609.6 -1.7964093168,52.42535326870001,609.6 -1.7915704121,52.4228998002,609.6 -1.7863823696,52.4207295265,609.6 -1.7808893971,52.4188609209,609.6 -1.7751382792,52.417309887,609.6 -1.7691779807,52.41608962379999,609.6 -1.7630592323,52.4152105147,609.6 -1.756834102,52.4146800394,609.6 -1.7505555556,52.4145027115,609.6 -1.7442770091,52.4146800394,609.6 -1.7380518788,52.4152105147,609.6 -1.7319331305,52.41608962379999,609.6 -1.7259728319,52.417309887,609.6 -1.720221714,52.4188609209,609.6 -1.7147287415,52.4207295265,609.6 -1.709540699,52.4228998002,609.6 -1.7047017943,52.42535326870001,609.6 -1.7002532833,52.4280690449,609.6 -1.6962331187,52.4310240045,609.6 -1.6926756266,52.4341929817,609.6 -1.6896112124,52.4375489828,609.6 -1.6870660999,52.4410634144,609.6 -1.6850621044,52.44470632659999,609.6 -1.6836164436,52.448446667,609.6 -1.6827415864,52.4522525448,609.6 -1.6824451421,52.4560915023,609.6 -1.6827297903,52.4599307911,609.6 -1.6835932529,52.4637376518,609.6 -1.685028309,52.467479593,609.6 -1.6870228506,52.4711246695,609.6 -1.689559982,52.4746417551,609.6 -1.6926181596,52.4780008096,609.6 -1.6961713722,52.4811731357,609.6 -1.7001893599,52.4841316255,609.6 -1.704637871,52.4868509931,609.6 -1.7094789525,52.48930799189999,609.6 -1.7146712746,52.4914816145,609.6 -1.7201704835,52.4933532735,609.6 -1.7259295825,52.49490696149999,609.6 -1.731899335,52.496129389,609.6 -1.7380286881,52.4970100989,609.6 -1.7442652129,52.497541557,609.6 -1.7505555556,52.4977192163,609.6 + + + + +
+ + EGRU210B BIRMINGHAM RWY 15 + 522953N 0014822W -
523011N 0014738W -
522934N 0014657W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to
522916N 0014741W -
522953N 0014822W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8062,52.4981111111,609.6 -1.7947085,52.48780075,609.6 -1.7908524655,52.48966253650001,609.6 -1.7867862897,52.4913496605,609.6 -1.7825311667,52.4928533333,609.6 -1.7940166667,52.50316111109999,609.6 -1.8062,52.4981111111,609.6 + + + + +
+ + EGRU210C BIRMINGHAM RWY 33 + 522442N 0014132W -
522424N 0014216W -
522510N 0014307W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522722N 0014502W to
522528N 0014223W -
522442N 0014132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6922444444,52.41161666669999,609.6 -1.7064432222,52.4244166667,609.6 -1.7102953441,52.42255677090001,609.6 -1.7143564184,52.4208713218,609.6 -1.7186053333,52.4193690556,609.6 -1.7044,52.4065666667,609.6 -1.6922444444,52.41161666669999,609.6 + + + + +
+ + EGRU211A DERBY + A circle, 2 NM radius, centred at 525135N 0013703W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6175,52.89300644979999,609.6 -1.6231586924,52.89282990499999,609.6 -1.6287572645,52.89230214629999,609.6 -1.6342362393,52.8914287806,609.6 -1.6395374187,52.89021908620001,609.6 -1.6446045057,52.88868591330001,609.6 -1.6493837057,52.886845547,609.6 -1.6538242998,52.884717533,609.6 -1.6578791853,52.88232446890001,609.6 -1.6615053761,52.8796917631,609.6 -1.6646644585,52.87684736330001,609.6 -1.6673229974,52.8738214592,609.6 -1.6694528885,52.8706461602,609.6 -1.6710316529,52.867355154,609.6 -1.6720426712,52.8639833481,609.6 -1.6724753548,52.860566499,609.6 -1.6723252526,52.8571408323,609.6 -1.6715940928,52.8537426589,609.6 -1.6702897581,52.8504079896,609.6 -1.6684261974,52.8471721543,609.6 -1.666023272,52.8440694281,609.6 -1.663106541,52.8411326689,609.6 -1.6597069867,52.8383929708,609.6 -1.6558606832,52.8358793358,609.6 -1.6516084125,52.83361836810001,609.6 -1.6469952321,52.8316339936,609.6 -1.6420699977,52.82994720839999,609.6 -1.6368848474,52.8285758576,609.6 -1.631494652,52.8275344477,609.6 -1.6259564376,52.8268339942,609.6 -1.620328785,52.8264819055,609.6 -1.614671215,52.8264819055,609.6 -1.6090435624,52.8268339942,609.6 -1.603505348,52.8275344477,609.6 -1.5981151526,52.8285758576,609.6 -1.5929300023,52.82994720839999,609.6 -1.5880047679,52.8316339936,609.6 -1.5833915875,52.83361836810001,609.6 -1.5791393168,52.8358793358,609.6 -1.5752930133,52.8383929708,609.6 -1.571893459,52.8411326689,609.6 -1.568976728,52.8440694281,609.6 -1.5665738026,52.8471721543,609.6 -1.5647102419,52.8504079896,609.6 -1.5634059072,52.8537426589,609.6 -1.5626747474,52.8571408323,609.6 -1.5625246452,52.860566499,609.6 -1.5629573288,52.8639833481,609.6 -1.5639683471,52.867355154,609.6 -1.5655471115,52.8706461602,609.6 -1.5676770026,52.8738214592,609.6 -1.5703355415,52.87684736330001,609.6 -1.5734946239,52.8796917631,609.6 -1.5771208147,52.88232446890001,609.6 -1.5811757002,52.884717533,609.6 -1.5856162943,52.886845547,609.6 -1.5903954943,52.88868591330001,609.6 -1.5954625813,52.89021908620001,609.6 -1.6007637607,52.8914287806,609.6 -1.6062427355,52.89230214629999,609.6 -1.6118413076,52.89282990499999,609.6 -1.6175,52.89300644979999,609.6 + + + + +
+ + EGRU211B DERBY RWY 05 + 524927N 0014006W -
524951N 0014042W -
525024N 0013942W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525001N 0013905W -
524927N 0014006W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6682780278,52.8241792222,609.6 -1.6514153333,52.8335263333,609.6 -1.6551790821,52.83548432919999,609.6 -1.6586362529,52.8376398054,609.6 -1.6617586667,52.8399752222,609.6 -1.6782875556,52.83081188889999,609.6 -1.6682780278,52.8241792222,609.6 + + + + +
+ + EGRU211C DERBY RWY 23 + 525336N 0013355W -
525312N 0013319W -
525240N 0013417W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525305N 0013452W -
525336N 0013355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5653483889,52.8933006111,609.6 -1.5810313611,52.88464044439999,609.6 -1.5774659925,52.88254823620001,609.6 -1.5742274102,52.8802699556,609.6 -1.571342,52.87782419439999,609.6 -1.5553245,52.886668,609.6 -1.5653483889,52.8933006111,609.6 + + + + +
+ + EGRU211D DERBY RWY 10 + 525144N 0014134W -
525216N 0014126W -
525210N 0014012W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525138N 0014021W -
525144N 0014134W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6926618056,52.86218136109999,609.6 -1.6724770556,52.8605240556,609.6 -1.6721355166,52.8635213229,609.6 -1.6713486888,52.866487734,609.6 -1.6701229167,52.8693991111,609.6 -1.6906521111,52.8710847222,609.6 -1.6926618056,52.86218136109999,609.6 + + + + +
+ + EGRU211E DERBY RWY 28 + 525131N 0013225W -
525059N 0013233W -
525106N 0013351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525138N 0013345W -
525131N 0013225W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5403897778,52.85866194439999,609.6 -1.5625221667,52.86050408330001,609.6 -1.5626315478,52.857500432,609.6 -1.5631879018,52.8545149834,609.6 -1.5641866111,52.8515720556,609.6 -1.5423988889,52.8497585556,609.6 -1.5403897778,52.85866194439999,609.6 + + + + +
+ + EGRU211F DERBY RWY 17 + 525422N 0013812W -
525427N 0013720W -
525335N 0013706W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
525330N 0013759W -
525422N 0013812W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.63679225,52.9061841944,609.6 -1.6331029167,52.89163966670001,609.6 -1.6282821584,52.8923609231,609.6 -1.6233734078,52.8928162187,609.6 -1.6184167222,52.8930018333,609.6 -1.6221006389,52.9075444444,609.6 -1.63679225,52.9061841944,609.6 + + + + +
+ + EGRU211G DERBY RWY 35 + 524849N 0013554W -
524844N 0013647W -
524935N 0013700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525135N 0013703W to
524940N 0013607W -
524849N 0013554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5983614722,52.8136583611,609.6 -1.6019306944,52.82780063890001,609.6 -1.6067449988,52.8270810369,609.6 -1.6116466805,52.82662702759999,609.6 -1.6165959167,52.8264423056,609.6 -1.6130214167,52.8122980833,609.6 -1.5983614722,52.8136583611,609.6 + + + + +
+ + EGRU212A WELLESBOURNE MOUNTFORD + A circle, 2 NM radius, centred at 521132N 0013652W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6144,52.2254963366,609.6 -1.6199734531,52.225319775,609.6 -1.6254876949,52.2247919659,609.6 -1.6308841471,52.22391851659999,609.6 -1.636105491,52.2227087055,609.6 -1.64109628,52.2211753837,609.6 -1.6458035312,52.21933483690001,609.6 -1.6501772909,52.2172066119,609.6 -1.6541711659,52.2148133076,609.6 -1.6577428169,52.2121803337,609.6 -1.6608544075,52.2093356402,609.6 -1.663473004,52.20630941869999,609.6 -1.6655709225,52.2031337812,609.6 -1.6671260192,52.19984241829999,609.6 -1.6681219212,52.1964702408,609.6 -1.6685481951,52.1930530088,609.6 -1.6684004526,52.1896269519,609.6 -1.6676803914,52.1862283849,609.6 -1.6663957719,52.1828933233,609.6 -1.6645603288,52.1796571014,609.6 -1.6621936216,52.1765539991,609.6 -1.659320822,52.1736168792,609.6 -1.6559724441,52.1708768403,609.6 -1.652184018,52.16836288899999,609.6 -1.6479957121,52.1661016338,609.6 -1.6434519062,52.1641170047,609.6 -1.6386007224,52.1624300014,609.6 -1.6334935167,52.1610584721,609.6 -1.6281843373,52.160016926,609.6 -1.6227293555,52.15931638050001,609.6 -1.617186275,52.15896424549999,609.6 -1.611613725,52.15896424549999,609.6 -1.6060706445,52.15931638050001,609.6 -1.6006156627,52.160016926,609.6 -1.5953064833,52.1610584721,609.6 -1.5901992776,52.1624300014,609.6 -1.5853480938,52.1641170047,609.6 -1.5808042879,52.1661016338,609.6 -1.576615982,52.16836288899999,609.6 -1.5728275559,52.1708768403,609.6 -1.569479178,52.1736168792,609.6 -1.5666063784,52.1765539991,609.6 -1.5642396712,52.1796571014,609.6 -1.5624042281,52.1828933233,609.6 -1.5611196086,52.1862283849,609.6 -1.5603995474,52.1896269519,609.6 -1.5602518049,52.1930530088,609.6 -1.5606780788,52.1964702408,609.6 -1.5616739808,52.19984241829999,609.6 -1.5632290775,52.2031337812,609.6 -1.565326996,52.20630941869999,609.6 -1.5679455925,52.2093356402,609.6 -1.5710571831,52.2121803337,609.6 -1.5746288341,52.2148133076,609.6 -1.5786227091,52.2172066119,609.6 -1.5829964688,52.21933483690001,609.6 -1.58770372,52.2211753837,609.6 -1.592694509,52.2227087055,609.6 -1.5979158529,52.22391851659999,609.6 -1.6033123051,52.2247919659,609.6 -1.6088265469,52.225319775,609.6 -1.6144,52.2254963366,609.6 + + + + +
+ + EGRU212B WELLESBOURNE MOUNTFORD RWY 05 + 520909N 0013952W -
520932N 0014029W -
521014N 0013920W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
520952N 0013840W -
520909N 0013952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6644833333,52.1525,609.6 -1.6445776111,52.1645690833,609.6 -1.6485160735,52.1663578639,609.6 -1.6521759225,52.1683580392,609.6 -1.6555272222,52.1705532778,609.6 -1.6747361111,52.1589055556,609.6 -1.6644833333,52.1525,609.6 + + + + +
+ + EGRU212C WELLESBOURNE MOUNTFORD RWY 23 + 521332N 0013352W -
521309N 0013315W -
521237N 0013408W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
521302N 0013443W -
521332N 0013352W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5644666667,52.2256444444,609.6 -1.5785241667,52.2171532222,609.6 -1.5750030605,52.2150594228,609.6 -1.5718046369,52.2127787035,609.6 -1.5689550278,52.21032975,609.6 -1.5542,52.2192416667,609.6 -1.5644666667,52.2256444444,609.6 + + + + +
+ + EGRU212D WELLESBOURNE MOUNTFORD RWY 18 + 521427N 0013738W -
521429N 0013645W -
521332N 0013639W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
521329N 0013731W -
521427N 0013738W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6271083333,52.240825,609.6 -1.6253352222,52.22481141670001,609.6 -1.6205050805,52.2252843723,609.6 -1.6156251224,52.22548782689999,609.6 -1.6107351667,52.2254201111,609.6 -1.6125027778,52.24143333329999,609.6 -1.6271083333,52.240825,609.6 + + + + +
+ + EGRU212E WELLESBOURNE MOUNTFORD RWY 36 + 520837N 0013606W -
520835N 0013659W -
520932N 0013705W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521132N 0013652W to
520935N 0013613W -
520837N 0013606W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6017222222,52.1435888889,609.6 -1.6034835,52.1596037222,609.6 -1.6083064442,52.1591316218,609.6 -1.6131788875,52.15892860939999,609.6 -1.61806125,52.1589963333,609.6 -1.6162944444,52.1429805556,609.6 -1.6017222222,52.1435888889,609.6 + + + + +
+ + EGRU213A COVENTRY + A circle, 2.5 NM radius, centred at 522211N 0012847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4796805556,52.41141982709999,609.6 -1.4859586139,52.4112421657,609.6 -1.4921829598,52.41071070140001,609.6 -1.4983003443,52.409829981,609.6 -1.5042584412,52.408607539,609.6 -1.5100062976,52.4070538323,609.6 -1.5154947736,52.40518215070001,609.6 -1.520676964,52.4030085014,609.6 -1.5255086022,52.40055147210001,609.6 -1.5299484387,52.3978320702,609.6 -1.5339585949,52.3948735425,609.6 -1.5375048854,52.3917011751,609.6 -1.5405571093,52.38834207600001,609.6 -1.5430893058,52.3848249429,609.6 -1.5450799728,52.38117981629999,609.6 -1.5465122469,52.3774378227,609.6 -1.5473740435,52.3736309076,609.6 -1.5476581549,52.3697915629,609.6 -1.5473623069,52.3659525485,609.6 -1.5464891734,52.3621466133,609.6 -1.545046348,52.3584062155,609.6 -1.5430462749,52.3547632464,609.6 -1.5405061376,52.35124875900001,609.6 -1.5374477087,52.3478927039,609.6 -1.5338971602,52.34472367480001,609.6 -1.5298848382,52.3417686664,609.6 -1.5254450017,52.33905284470001,609.6 -1.5206155294,52.33659933460001,609.6 -1.5154375968,52.3344290237,609.6 -1.5099553259,52.332560386,609.6 -1.5042154102,52.3310093251,609.6 -1.4982667195,52.3297890406,609.6 -1.4921598862,52.3289099161,609.6 -1.4859468772,52.3283794315,609.6 -1.4796805556,52.3282021004,609.6 -1.4734142339,52.3283794315,609.6 -1.4672012249,52.3289099161,609.6 -1.4610943916,52.3297890406,609.6 -1.4551457009,52.3310093251,609.6 -1.4494057852,52.332560386,609.6 -1.4439235143,52.3344290237,609.6 -1.4387455817,52.33659933460001,609.6 -1.4339161094,52.33905284470001,609.6 -1.4294762729,52.3417686664,609.6 -1.4254639509,52.34472367480001,609.6 -1.4219134024,52.3478927039,609.6 -1.4188549735,52.35124875900001,609.6 -1.4163148362,52.3547632464,609.6 -1.4143147631,52.3584062155,609.6 -1.4128719377,52.3621466133,609.6 -1.4119988042,52.3659525485,609.6 -1.4117029562,52.3697915629,609.6 -1.4119870676,52.3736309076,609.6 -1.4128488642,52.3774378227,609.6 -1.4142811383,52.38117981629999,609.6 -1.4162718053,52.3848249429,609.6 -1.4188040018,52.38834207600001,609.6 -1.4218562257,52.3917011751,609.6 -1.4254025162,52.3948735425,609.6 -1.4294126724,52.3978320702,609.6 -1.4338525089,52.40055147210001,609.6 -1.4386841471,52.4030085014,609.6 -1.4438663375,52.40518215070001,609.6 -1.4493548135,52.4070538323,609.6 -1.4551026699,52.408607539,609.6 -1.4610607668,52.409829981,609.6 -1.4671781513,52.41071070140001,609.6 -1.4734024973,52.4112421657,609.6 -1.4796805556,52.41141982709999,609.6 + + + + +
+ + EGRU213B COVENTRY RWY 05 + 521952N 0013215W -
522016N 0013250W -
522042N 0013204W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to
522019N 0013128W -
521952N 0013215W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5373944444,52.33113611109999,609.6 -1.52439425,52.3384789444,609.6 -1.5279657452,52.3405328775,609.6 -1.5312866019,52.3427390404,609.6 -1.5343395556,52.3450859722,609.6 -1.5473305556,52.3377472222,609.6 -1.5373944444,52.33113611109999,609.6 + + + + +
+ + EGRU213C COVENTRY RWY 23 + 522430N 0012519W -
522407N 0012443W -
522340N 0012530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522211N 0012847W to
522404N 0012606W -
522430N 0012519W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4218777778,52.4084555556,609.6 -1.4349076111,52.40112836110001,609.6 -1.4313348092,52.3990715077,609.6 -1.4280140169,52.39686238180001,609.6 -1.4249625,52.3945125,609.6 -1.4119222222,52.4018444444,609.6 -1.4218777778,52.4084555556,609.6 + + + + +
+ + EGRU214A EAST MIDLANDS + A circle, 2.5 NM radius, centred at 524952N 0011940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3277777778,52.8727165679,609.6 -1.3341222329,52.8725389176,609.6 -1.3404124051,52.8720074866,609.6 -1.3465944797,52.87112682170001,609.6 -1.3526155747,52.8699044571,609.6 -1.3584241967,52.8683508497,609.6 -1.3639706843,52.8664792888,609.6 -1.3692076354,52.8643057815,609.6 -1.3740903145,52.86184891479999,609.6 -1.3785770361,52.8591296956,609.6 -1.3826295214,52.8561713699,609.6 -1.3862132249,52.85299922270001,609.6 -1.3892976278,52.849640361,609.6 -1.391856497,52.846123481,609.6 -1.3938681056,52.8424786217,609.6 -1.3953154151,52.8387369078,609.6 -1.3961862161,52.8349302827,609.6 -1.396473228,52.8310912361,609.6 -1.3961741563,52.8272525253,609.6 -1.3952917062,52.8234468966,609.6 -1.393833555,52.8197068054,609.6 -1.3918122811,52.8160641401,609.6 -1.3892452525,52.8125499505,609.6 -1.3861544737,52.8091941841,609.6 -1.3825663951,52.80602543169999,609.6 -1.3785116842,52.8030706845,609.6 -1.3740249626,52.8003551059,609.6 -1.369144509,52.7979018179,609.6 -1.363911933,52.7957317053,609.6 -1.3583718213,52.7938632398,609.6 -1.3525713588,52.7923123228,609.6 -1.3465599289,52.7910921522,609.6 -1.3403886961,52.79021311,609.6 -1.3341101731,52.7896826753,609.6 -1.3277777778,52.78950536090001,609.6 -1.3214453824,52.7896826753,609.6 -1.3151668594,52.79021311,609.6 -1.3089956266,52.7910921522,609.6 -1.3029841968,52.7923123228,609.6 -1.2971837343,52.7938632398,609.6 -1.2916436225,52.7957317053,609.6 -1.2864110466,52.7979018179,609.6 -1.2815305929,52.8003551059,609.6 -1.2770438713,52.8030706845,609.6 -1.2729891605,52.80602543169999,609.6 -1.2694010819,52.8091941841,609.6 -1.2663103031,52.8125499505,609.6 -1.2637432744,52.8160641401,609.6 -1.2617220006,52.8197068054,609.6 -1.2602638494,52.8234468966,609.6 -1.2593813993,52.8272525253,609.6 -1.2590823275,52.8310912361,609.6 -1.2593693395,52.8349302827,609.6 -1.2602401405,52.8387369078,609.6 -1.2616874499,52.8424786217,609.6 -1.2636990586,52.846123481,609.6 -1.2662579278,52.849640361,609.6 -1.2693423307,52.85299922270001,609.6 -1.2729260341,52.8561713699,609.6 -1.2769785194,52.8591296956,609.6 -1.2814652411,52.86184891479999,609.6 -1.2863479202,52.8643057815,609.6 -1.2915848713,52.8664792888,609.6 -1.2971313589,52.8683508497,609.6 -1.3029399809,52.8699044571,609.6 -1.3089610759,52.87112682170001,609.6 -1.3151431504,52.8720074866,609.6 -1.3214333226,52.8725389176,609.6 -1.3277777778,52.8727165679,609.6 + + + + +
+ + EGRU214B EAST MIDLANDS RWY 09 + 524929N 0012515W -
525002N 0012517W -
525003N 0012347W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to
524931N 0012345W -
524929N 0012515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4208305556,52.824775,609.6 -1.3957835,52.8252495278,609.6 -1.3963064082,52.8282329641,609.6 -1.3964730465,52.8312314664,609.6 -1.3962824722,52.8342294444,609.6 -1.421275,52.8337555556,609.6 -1.4208305556,52.824775,609.6 + + + + +
+ + EGRU214C EAST MIDLANDS RWY 27 + 525014N 0011405W -
524941N 0011403W -
524940N 0011534W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524952N 0011940W to
525012N 0011535W -
525014N 0011405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2346666667,52.83716666670001,609.6 -1.2597063611,52.8367260278,609.6 -1.2592174925,52.8337397508,609.6 -1.2590853456,52.8307399007,609.6 -1.2593105556,52.82774208330001,609.6 -1.2342138889,52.8281833333,609.6 -1.2346666667,52.83716666670001,609.6 + + + + +
+ + EGRU215A NOTTINGHAM + A circle, 2 NM radius, centred at 525515N 0010448W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.08,52.95411721650001,609.6 -1.0856666656,52.95394067319999,609.6 -1.0912731259,52.9534129191,609.6 -1.0967598197,52.95253956100001,609.6 -1.1020684668,52.95132987720001,609.6 -1.1071426907,52.9497967178,609.6 -1.1119286206,52.9479563679,609.6 -1.1163754663,52.94582837309999,609.6 -1.1204360586,52.94343533090001,609.6 -1.1240673509,52.94080264940001,609.6 -1.1272308755,52.9379582765,609.6 -1.1298931505,52.9349324012,609.6 -1.1320260322,52.93175713309999,609.6 -1.1336070103,52.9284661594,609.6 -1.1346194424,52.92509438740001,609.6 -1.1350527254,52.9216775732,609.6 -1.1349024025,52.9182519421,609.6 -1.1341702043,52.9148538046,609.6 -1.1328640255,52.9115191711,609.6 -1.1309978346,52.90828337109999,609.6 -1.1285915213,52.9051806792,609.6 -1.1256706811,52.902243953,609.6 -1.1222663398,52.8995042861,609.6 -1.1184146226,52.89699068,609.6 -1.1141563688,52.8947297385,609.6 -1.1095366993,52.8927453873,609.6 -1.1046045384,52.8910586221,609.6 -1.0994120974,52.8896872876,609.6 -1.0940143241,52.8886458902,609.6 -1.0884683244,52.8879454451,609.6 -1.0828327612,52.88759336060001,609.6 -1.0771672388,52.88759336060001,609.6 -1.0715316756,52.8879454451,609.6 -1.0659856759,52.8886458902,609.6 -1.0605879026,52.8896872876,609.6 -1.0553954616,52.8910586221,609.6 -1.0504633007,52.8927453873,609.6 -1.0458436312,52.8947297385,609.6 -1.0415853774,52.89699068,609.6 -1.0377336602,52.8995042861,609.6 -1.0343293189,52.902243953,609.6 -1.0314084787,52.9051806792,609.6 -1.0290021654,52.90828337109999,609.6 -1.0271359745,52.9115191711,609.6 -1.0258297957,52.9148538046,609.6 -1.0250975975,52.9182519421,609.6 -1.0249472746,52.9216775732,609.6 -1.0253805576,52.92509438740001,609.6 -1.0263929897,52.9284661594,609.6 -1.0279739678,52.93175713309999,609.6 -1.0301068495,52.9349324012,609.6 -1.0327691245,52.9379582765,609.6 -1.0359326491,52.94080264940001,609.6 -1.0395639414,52.94343533090001,609.6 -1.0436245337,52.94582837309999,609.6 -1.0480713794,52.9479563679,609.6 -1.0528573093,52.9497967178,609.6 -1.0579315332,52.95132987720001,609.6 -1.0632401803,52.95253956100001,609.6 -1.0687268741,52.9534129191,609.6 -1.0743333344,52.95394067319999,609.6 -1.08,52.95411721650001,609.6 + + + + +
+ + EGRU215B NOTTINGHAM RWY 03 + 525228N 0010627W -
525244N 0010715W -
525333N 0010632W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525320N 0010542W -
525228N 0010627W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1075944444,52.8745638889,609.6 -1.09513225,52.8888314444,609.6 -1.0998531952,52.8897890795,609.6 -1.1044119397,52.89100072210001,609.6 -1.1087712222,52.8924564722,609.6 -1.120725,52.87876666670001,609.6 -1.1075944444,52.8745638889,609.6 + + + + +
+ + EGRU215C NOTTINGHAM RWY 21 + 525754N 0010243W -
525738N 0010156W -
525647N 0010241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525704N 0010327W -
525754N 0010243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0454,52.9648666667,609.6 -1.0573920833,52.9511852778,609.6 -1.0529431955,52.9498260518,609.6 -1.0487162267,52.94822936720001,609.6 -1.0447458056,52.9464083333,609.6 -1.0322444444,52.96066666670001,609.6 -1.0454,52.9648666667,609.6 + + + + +
+ + EGRU215D NOTTINGHAM RWY 09 + 525452N 0010933W -
525524N 0010935W -
525526N 0010805W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525454N 0010803W -
525452N 0010933W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1592722222,52.9143111111,609.6 -1.1341868056,52.9149089167,609.6 -1.1348516491,52.9178856696,609.6 -1.1350698583,52.9208865282,609.6 -1.1348395556,52.9238870556,609.6 -1.1598416667,52.9232916667,609.6 -1.1592722222,52.9143111111,609.6 + + + + +
+ + EGRU215E NOTTINGHAM RWY 27 + 525537N 0005958W -
525505N 0005956W -
525503N 0010131W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525515N 0010448W to
525535N 0010133W -
525537N 0005958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9993333332999998,52.9270222222,609.6 -1.0257090556,52.9264241111,609.6 -1.0250980782,52.9234437562,609.6 -1.0249341478,52.9204422491,609.6 -1.0252185,52.91744402780001,609.6 -0.9987611111,52.9180444444,609.6 -0.9993333332999998,52.9270222222,609.6 + + + + +
+ + EGRU216A LEICESTER + A circle, 2 NM radius, centred at 523628N 0010155W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0319444444,52.6410634276,609.6 -1.0375705691,52.6408868765,609.6 -1.0431369207,52.6403590989,609.6 -1.0485843657,52.6394857017,609.6 -1.053855042,52.6382759635,609.6 -1.0588929776,52.6367427346,609.6 -1.0636446878,52.6349023004,609.6 -1.0680597463,52.6327742071,609.6 -1.0720913215,52.6303810526,609.6 -1.0756966742,52.627748246,609.6 -1.0788376114,52.6249037357,609.6 -1.0814808896,52.62187771209999,609.6 -1.0835985651,52.6187022857,609.6 -1.085168287,52.6154111452,609.6 -1.08617353,52.6120391994,609.6 -1.0866037648,52.60862220600001,609.6 -1.0864545645,52.6051963924,609.6 -1.0857276454,52.6017980707,609.6 -1.0844308436,52.59846325349999,609.6 -1.082578026,52.5952272725,609.6 -1.0801889387,52.5921244045,609.6 -1.0772889928,52.5891875093,609.6 -1.0739089916,52.5864476827,609.6 -1.0700848014,52.5839339285,609.6 -1.0658569699,52.5816728523,609.6 -1.0612702954,52.5796883817,609.6 -1.0563733535,52.5780015143,609.6 -1.0512179835,52.5766300961,609.6 -1.0458587418,52.5755886349,609.6 -1.0403523279,52.57488814669999,609.6 -1.0347569877,52.57453604049999,609.6 -1.0291319012,52.57453604049999,609.6 -1.023536561,52.57488814669999,609.6 -1.0180301471,52.5755886349,609.6 -1.0126709054,52.5766300961,609.6 -1.0075155354,52.5780015143,609.6 -1.0026185935,52.5796883817,609.6 -0.998031919,52.5816728523,609.6 -0.9938040874,52.5839339285,609.6 -0.9899798973,52.5864476827,609.6 -0.9865998961,52.5891875093,609.6 -0.9836999502,52.5921244045,609.6 -0.9813108629,52.5952272725,609.6 -0.9794580453000001,52.59846325349999,609.6 -0.9781612435,52.6017980707,609.6 -0.9774343243999999,52.6051963924,609.6 -0.9772851241,52.60862220600001,609.6 -0.9777153589000001,52.6120391994,609.6 -0.9787206019,52.6154111452,609.6 -0.9802903238000001,52.6187022857,609.6 -0.9824079993,52.62187771209999,609.6 -0.9850512774,52.6249037357,609.6 -0.9881922147000001,52.627748246,609.6 -0.9917975674,52.6303810526,609.6 -0.9958291424999999,52.6327742071,609.6 -1.000244201,52.6349023004,609.6 -1.0049959113,52.6367427346,609.6 -1.0100338469,52.6382759635,609.6 -1.0153045232,52.6394857017,609.6 -1.0207519682,52.6403590989,609.6 -1.0263183198,52.6408868765,609.6 -1.0319444444,52.6410634276,609.6 + + + + +
+ + EGRU216B LEICESTER RWY 04 + 523354N 0010406W -
523413N 0010448W -
523454N 0010358W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523438N 0010312W -
523354N 0010406W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0683138889,52.56495,609.6 -1.0533300833,52.5771455833,609.6 -1.0578004505,52.57845176989999,609.6 -1.0620583556,52.5799992746,609.6 -1.0660687778,52.5817753889,609.6 -1.0801166667,52.5703388889,609.6 -1.0683138889,52.56495,609.6 + + + + +
+ + EGRU216C LEICESTER RWY 22 + 523845N 0005914W -
523826N 0005831W -
523744N 0005923W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523806N 0010002W -
523845N 0005914W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9871722222,52.6458638889,609.6 -1.0005339722,52.63502688890001,609.6 -0.9966043646999999,52.6331813756,609.6 -0.9929662177,52.6311266371,609.6 -0.9896495,52.6288796111,609.6 -0.9753499999999999,52.640475,609.6 -0.9871722222,52.6458638889,609.6 + + + + +
+ + EGRU216D LEICESTER RWY 06 + 523417N 0010449W -
523441N 0010525W -
523513N 0010428W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523450N 0010349W -
523417N 0010449W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0803583333,52.5713138889,609.6 -1.0636405833,52.5806598333,609.6 -1.0675359805,52.58251512939999,609.6 -1.0711404251,52.5845772236,609.6 -1.0744244167,52.58682925000001,609.6 -1.090325,52.57793888890001,609.6 -1.0803583333,52.5713138889,609.6 + + + + +
+ + EGRU216E LEICESTER RWY 24 + 523827N 0005840W -
523803N 0005804W -
523729N 0005905W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523754N 0005938W -
523827N 0005840W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9776805556,52.6407972222,609.6 -0.9939642500000001,52.6317283056,609.6 -0.9905625572,52.6295401098,609.6 -0.9875002127999999,52.6271736895,609.6 -0.9848022778,52.6246484444,609.6 -0.9677,52.6341722222,609.6 -0.9776805556,52.6407972222,609.6 + + + + +
+ + EGRU216F LEICESTER RWY 10 + 523631N 0010647W -
523703N 0010641W -
523657N 0010506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523625N 0010512W -
523631N 0010647W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1130722222,52.6085833333,609.6 -1.0866007222,52.6068874444,609.6 -1.0865119041,52.6098905627,609.6 -1.0859786876,52.61287657690001,609.6 -1.0850053333,52.6158211667,609.6 -1.1115138889,52.6175194444,609.6 -1.1130722222,52.6085833333,609.6 + + + + +
+ + EGRU216G LEICESTER RWY 28 + 523626N 0005704W -
523554N 0005709W -
523600N 0005844W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523632N 0005838W -
523626N 0005704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.950975,52.6071416667,609.6 -0.9772961944,52.6088584167,609.6 -0.9773605349,52.6058550628,609.6 -0.9778692787,52.6028674649,609.6 -0.9788181944,52.5999199444,609.6 -0.9525333333000001,52.59820555560001,609.6 -0.950975,52.6071416667,609.6 + + + + +
+ + EGRU216H LEICESTER RWY 15 + 523841N 0010436W -
523857N 0010350W -
523818N 0010314W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523801N 0010359W -
523841N 0010436W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.076675,52.644675,609.6 -1.0663972778,52.6336289722,609.6 -1.0624252862,52.6354151885,609.6 -1.0582044025,52.6369760432,609.6 -1.0537690556,52.6382987778,609.6 -1.0638138889,52.6490972222,609.6 -1.076675,52.644675,609.6 + + + + +
+ + EGRU216I LEICESTER RWY 33 + 523401N 0005915W -
523345N 0010001W -
523435N 0010048W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523450N 0010001W -
523401N 0005915W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9875722222,52.56698055559999,609.6 -1.0002493889,52.5806593611,609.6 -1.0043947656,52.5790293299,609.6 -1.0087643261,52.5776335702,609.6 -1.0133225,52.5764834444,609.6 -1.0004111111,52.56255555560001,609.6 -0.9875722222,52.56698055559999,609.6 + + + + +
+ + EGRU216J LEICESTER RWY 16 + 523837N 0010440W -
523854N 0010355W -
523817N 0010318W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523759N 0010403W -
523837N 0010440W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0777805556,52.6435361111,609.6 -1.0673638056,52.6331404444,609.6 -1.0634615593,52.63498123910001,609.6 -1.059302093,52.63660032759999,609.6 -1.0549193333,52.6379845,609.6 -1.0651611111,52.6482083333,609.6 -1.0777805556,52.6435361111,609.6 + + + + +
+ + EGRU216K LEICESTER RWY 34 + 523405N 0005906W -
523348N 0005952W -
523437N 0010040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 523628N 0010155W to
523453N 0005954W -
523405N 0005906W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9850805556000001,52.5681166667,609.6 -0.9984237778,52.5814858611,609.6 -1.0024525214,52.5797529201,609.6 -1.00672106,52.5782481656,609.6 -1.0111946667,52.5769838333,609.6 -0.9976777778,52.5634444444,609.6 -0.9850805556000001,52.5681166667,609.6 + + + + +
+ + EGRU217A NORTHAMPTON/SYWELL + A circle, 2 NM radius, centred at 521822N 0004732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7922222222,52.3393984685,609.6 -0.7978099840999999,52.3392219097,609.6 -0.8033383821,52.3386941093,609.6 -0.8087486871,52.3378206743,609.6 -0.8139834327,52.3366108832,609.6 -0.8189870296,52.33507758699999,609.6 -0.8237063585999999,52.3332370711,609.6 -0.8280913375999999,52.3311088823,609.6 -0.8320954543,52.3287156191,609.6 -0.8356762609,52.3260826912,609.6 -0.8387958239,52.32323804800001,609.6 -0.8414211255,52.3202118809,609.6 -0.8435244113000001,52.3170363014,609.6 -0.8450834812,52.3137449995,609.6 -0.8460819208,52.3103728857,609.6 -0.8465092708,52.3069557192,609.6 -0.8463611324,52.303529729,609.6 -0.8456392082999999,52.3001312293,609.6 -0.8443512793,52.2967962348,609.6 -0.8425111163,52.293560079,609.6 -0.8401383293,52.290457041,609.6 -0.8372581551,52.2875199827,609.6 -0.8339011864,52.284780002,609.6 -0.8301030446,52.2822661048,609.6 -0.8259040010000001,52.2800048986,609.6 -0.8213485493,52.278020313,609.6 -0.8164849347000001,52.27633334690001,609.6 -0.8113646445,52.2749618482,609.6 -0.806041865,52.2739203253,609.6 -0.8005729110000001,52.2732197955,609.6 -0.7950156334,52.27286766840001,609.6 -0.7894288111,52.27286766840001,609.6 -0.7838715335000001,52.2732197955,609.6 -0.7784025793999999,52.2739203253,609.6 -0.7730797999,52.2749618482,609.6 -0.7679595097,52.27633334690001,609.6 -0.7630958952,52.278020313,609.6 -0.7585404435000001,52.2800048986,609.6 -0.7543413999000002,52.2822661048,609.6 -0.7505432581,52.284780002,609.6 -0.7471862893000001,52.2875199827,609.6 -0.7443061150999999,52.290457041,609.6 -0.7419333280999999,52.293560079,609.6 -0.7400931651,52.2967962348,609.6 -0.7388052361999999,52.3001312293,609.6 -0.7380833120999999,52.303529729,609.6 -0.7379351735999999,52.3069557192,609.6 -0.7383625236,52.3103728857,609.6 -0.7393609633,52.3137449995,609.6 -0.7409200331,52.3170363014,609.6 -0.7430233189,52.3202118809,609.6 -0.7456486206,52.32323804800001,609.6 -0.7487681836,52.3260826912,609.6 -0.7523489901,52.3287156191,609.6 -0.7563531068,52.3311088823,609.6 -0.7607380858,52.3332370711,609.6 -0.7654574149,52.33507758699999,609.6 -0.7704610117999999,52.3366108832,609.6 -0.7756957574,52.3378206743,609.6 -0.7811060622999999,52.3386941093,609.6 -0.7866344602999999,52.3392219097,609.6 -0.7922222222,52.3393984685,609.6 + + + + +
+ + EGRU217B NORTHAMPTON/SYWELL RWY 03L + 521535N 0004908W -
521549N 0004956W -
521641N 0004917W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521627N 0004829W -
521535N 0004908W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8188444444000001,52.25975,609.6 -0.8080391111,52.2742679167,609.6 -0.812654855,52.2752715462,609.6 -0.8171045318000001,52.27652619300001,609.6 -0.8213519722,52.2780216389,609.6 -0.8321666666999999,52.2634861111,609.6 -0.8188444444000001,52.25975,609.6 + + + + +
+ + EGRU217C NORTHAMPTON/SYWELL RWY 21R + 522108N 0004558W -
522054N 0004510W -
522003N 0004548W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
522017N 0004636W -
522108N 0004558W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7660416667000001,52.3521972222,609.6 -0.7766436667,52.3380003611,609.6 -0.7720147602,52.3370096914,609.6 -0.7675507069,52.3357673179,609.6 -0.7632879166999998,52.3342833611,609.6 -0.7526944444,52.3484638889,609.6 -0.7660416667000001,52.3521972222,609.6 + + + + +
+ + EGRU217D NORTHAMPTON/SYWELL RWY 03R + 521535N 0004902W -
521548N 0004950W -
521639N 0004912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521626N 0004824W -
521535N 0004902W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.817225,52.2596388889,609.6 -0.8065377222,52.2740019167,609.6 -0.8112001893,52.2749240222,609.6 -0.8157083104,52.2761001429,609.6 -0.8200254167000001,52.27752069440001,609.6 -0.8305472222,52.263375,609.6 -0.817225,52.2596388889,609.6 + + + + +
+ + EGRU217E NORTHAMPTON/SYWELL RWY 21L + 522102N 0004556W -
522049N 0004508W -
522002N 0004543W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
522016N 0004631W -
522102N 0004556W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7655472222,52.35060277780001,609.6 -0.77516825,52.3377156111,609.6 -0.7705856744,52.3366441745,609.6 -0.7661797483,52.33532380890001,609.6 -0.7619864167,52.3337653056,609.6 -0.7522000000000001,52.3468694444,609.6 -0.7655472222,52.35060277780001,609.6 + + + + +
+ + EGRU217F NORTHAMPTON/SYWELL RWY 05 + 521618N 0005049W -
521643N 0005121W -
521715N 0005014W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521651N 0004939W -
521618N 0005049W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8469,52.2715333333,609.6 -0.8275625,52.2808424722,609.6 -0.8311402354,52.28290235400001,609.6 -0.834400312,52.2851519226,609.6 -0.8373160833,52.2875728056,609.6 -0.8559361111,52.2786083333,609.6 -0.8469,52.2715333333,609.6 + + + + +
+ + EGRU217G NORTHAMPTON/SYWELL RWY 23 + 522015N 0004401W -
521949N 0004328W -
521916N 0004437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521943N 0004507W -
522015N 0004401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7335999999999999,52.33738611110001,609.6 -0.7520706944000001,52.32852977780001,609.6 -0.7489313660999999,52.3262153965,609.6 -0.7461463394999999,52.3237366888,609.6 -0.7437383333000002,52.3211139444,609.6 -0.72455,52.3303138889,609.6 -0.7335999999999999,52.33738611110001,609.6 + + + + +
+ + EGRU217H NORTHAMPTON/SYWELL RWY 14 + 522016N 0005109W -
522039N 0005032W -
522000N 0004925W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521938N 0005004W -
522016N 0005109W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8524527778,52.3377472222,609.6 -0.8343298333,52.3271384167,609.6 -0.8310595854,52.32938324580001,609.6 -0.8274715191999998,52.3314378811,609.6 -0.8235949444,52.3332855,609.6 -0.8423083333000001,52.3442416667,609.6 -0.8524527778,52.3377472222,609.6 + + + + +
+ + EGRU217I NORTHAMPTON/SYWELL RWY 32 + 521638N 0004340W -
521614N 0004417W -
521653N 0004522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 521822N 0004732W to
521717N 0004448W -
521638N 0004340W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.7279055556,52.2771305556,609.6 -0.7465651944000001,52.2880981667,609.6 -0.7494051075999999,52.2856446324,609.6 -0.7525943514,52.2833582938,609.6 -0.7561068611,52.28125780559999,609.6 -0.7380333333,52.2706361111,609.6 -0.7279055556,52.2771305556,609.6 + + + + +
+ + EGRU218A CRANFIELD + A circle, 2 NM radius, centred at 520420N 0003700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6166666667,52.1055109067,609.6 -0.6222251498,52.105334342,609.6 -0.6277245811,52.1048065238,609.6 -0.6331065404,52.10393305929999,609.6 -0.6383138633,52.1027232271,609.6 -0.6432912525,52.1011898783,609.6 -0.6479858678,52.0993492989,609.6 -0.6523478896,52.0972210357,609.6 -0.6563310496,52.0948276879,609.6 -0.6598931220000001,52.0921946656,609.6 -0.6629963717,52.08934991900001,609.6 -0.6656079531,52.0863236401,609.6 -0.6677002562,52.0831479414,609.6 -0.6692511960999999,52.0798565142,609.6 -0.670244443,52.0764842696,609.6 -0.6706695909,52.0730669685,609.6 -0.6705222627,52.0696408411,609.6 -0.6698041505,52.06624220319999,609.6 -0.6685229932,52.0629070708,609.6 -0.6666924882,52.0596707793,609.6 -0.6643321417,52.0565676093,609.6 -0.6614670575,52.0536304244,609.6 -0.6581276673999999,52.05089032410001,609.6 -0.6543494062,52.0483763159,609.6 -0.6501723341,52.0461150089,609.6 -0.6456407123,52.04413033400001,609.6 -0.6408025339,52.0424432914,609.6 -0.6357090174,52.04107173000001,609.6 -0.6304140667,52.0400301594,609.6 -0.6249737029,52.03932959739999,609.6 -0.6194454757,52.03897745410001,609.6 -0.6138878577,52.03897745410001,609.6 -0.6083596304,52.03932959739999,609.6 -0.6029192665999999,52.0400301594,609.6 -0.5976243159,52.04107173000001,609.6 -0.5925307995,52.0424432914,609.6 -0.5876926211,52.04413033400001,609.6 -0.5831609992,52.0461150089,609.6 -0.5789839272,52.0483763159,609.6 -0.5752056659,52.05089032410001,609.6 -0.5718662758,52.0536304244,609.6 -0.5690011916,52.0565676093,609.6 -0.5666408451,52.0596707793,609.6 -0.5648103401,52.0629070708,609.6 -0.5635291828,52.06624220319999,609.6 -0.5628110707,52.0696408411,609.6 -0.5626637424000001,52.0730669685,609.6 -0.5630888903,52.0764842696,609.6 -0.5640821372,52.0798565142,609.6 -0.5656330771,52.0831479414,609.6 -0.5677253802,52.0863236401,609.6 -0.5703369616,52.08934991900001,609.6 -0.5734402114,52.0921946656,609.6 -0.5770022838,52.0948276879,609.6 -0.5809854437,52.0972210357,609.6 -0.5853474655999999,52.0993492989,609.6 -0.5900420809,52.1011898783,609.6 -0.59501947,52.1027232271,609.6 -0.6002267929,52.10393305929999,609.6 -0.6056087522,52.1048065238,609.6 -0.6111081835,52.105334342,609.6 -0.6166666667,52.1055109067,609.6 + + + + +
+ + EGRU218B CRANFIELD RWY 03 + 520134N 0003915W -
520151N 0004000W -
520247N 0003903W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to
520230N 0003819W -
520134N 0003915W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6541416667,52.0262083333,609.6 -0.6385356666999999,52.0417852222,609.6 -0.6428961638,52.0431237873,609.6 -0.6470435365,52.0446991176,609.6 -0.6509440556,52.0464984167,609.6 -0.6665305556,52.0309361111,609.6 -0.6541416667,52.0262083333,609.6 + + + + +
+ + EGRU218C CRANFIELD RWY 21 + 520710N 0003439W -
520653N 0003355W -
520552N 0003456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520420N 0003700W to
520609N 0003541W -
520710N 0003439W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5776055556,52.11955,609.6 -0.5946302778,52.1026172778,609.6 -0.5902709864,52.1012692712,609.6 -0.5861270565,52.09968460289999,609.6 -0.5822322778,52.09787619440001,609.6 -0.5651888889,52.1148222222,609.6 -0.5776055556,52.11955,609.6 + + + + +
+ + EGRU219A BARKSTON HEATH + A circle, 2 NM radius, centred at 525747N 0003337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5603222222000001,52.99626697899999,609.6 -0.565994404,52.9960904368,609.6 -0.5716063218,52.9955626858,609.6 -0.577098356,52.994689333,609.6 -0.5824121696,52.99347965639999,609.6 -0.5874913311,52.9919465064,609.6 -0.5922819171,52.9901061679,609.6 -0.5967330879,52.9879781863,609.6 -0.6007976284,52.9855851591,609.6 -0.6044324502,52.9829524945,609.6 -0.6075990482,52.9801081399,609.6 -0.6102639079,52.9770822846,609.6 -0.6123988586,52.9739070377,609.6 -0.6139813683000001,52.9706160864,609.6 -0.6149947786,52.9672443378,609.6 -0.6154284763,52.9638275476,609.6 -0.6152780005,52.96040194119999,609.6 -0.6145450841,52.9570038284,609.6 -0.6132376293,52.9536692196,609.6 -0.6113696187,52.950433444,609.6 -0.6089609616,52.9473307757,609.6 -0.6060372784,52.9443940723,609.6 -0.6026296253,52.94165442679999,609.6 -0.5987741625,52.93914084069999,609.6 -0.5945117693999999,52.9368799173,609.6 -0.5898876105,52.9348955822,609.6 -0.5849506575,52.9332088307,609.6 -0.5797531725,52.9318375075,609.6 -0.5743501564,52.93079611870001,609.6 -0.5687987704,52.9300956793,609.6 -0.5631577344000001,52.9297435978,609.6 -0.5574867100999999,52.9297435978,609.6 -0.551845674,52.9300956793,609.6 -0.546294288,52.93079611870001,609.6 -0.540891272,52.9318375075,609.6 -0.5356937869,52.9332088307,609.6 -0.530756834,52.9348955822,609.6 -0.526132675,52.9368799173,609.6 -0.5218702819,52.93914084069999,609.6 -0.5180148192,52.94165442679999,609.6 -0.5146071661,52.9443940723,609.6 -0.5116834828,52.9473307757,609.6 -0.5092748257,52.950433444,609.6 -0.5074068151,52.9536692196,609.6 -0.5060993604,52.9570038284,609.6 -0.5053664439,52.96040194119999,609.6 -0.5052159682,52.9638275476,609.6 -0.5056496659,52.9672443378,609.6 -0.5066630762,52.9706160864,609.6 -0.5082455858,52.9739070377,609.6 -0.5103805365,52.9770822846,609.6 -0.5130453963,52.9801081399,609.6 -0.5162119943,52.9829524945,609.6 -0.519846816,52.9855851591,609.6 -0.5239113565,52.9879781863,609.6 -0.5283625273,52.9901061679,609.6 -0.5331531134,52.9919465064,609.6 -0.5382322748,52.99347965639999,609.6 -0.5435460884,52.994689333,609.6 -0.5490381227,52.9955626858,609.6 -0.5546500404,52.9960904368,609.6 -0.5603222222000001,52.99626697899999,609.6 + + + + +
+ + EGRU219B BARKSTON HEATH RWY 06 + 525553N 0003743W -
525620N 0003812W -
525656N 0003637W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525629N 0003608W -
525553N 0003743W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6285518889,52.931293,609.6 -0.6023251944,52.9414361667,609.6 -0.6053708766,52.9438101274,609.6 -0.6080502032,52.9463402205,609.6 -0.6103413333,52.94900586110001,609.6 -0.6365603611,52.9388649167,609.6 -0.6285518889,52.931293,609.6 + + + + +
+ + EGRU219C BARKSTON HEATH RWY 24 + 525943N 0002924W -
525916N 0002856W -
525837N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525904N 0003106W -
525943N 0002924W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4901250278,52.99536802779999,609.6 -0.51829125,52.9845253889,609.6 -0.5152459863,52.9821499092,609.6 -0.5125682452,52.979618365,609.6 -0.5102798056,52.9769513889,609.6 -0.4821061111,52.9877961667,609.6 -0.4901250278,52.99536802779999,609.6 + + + + +
+ + EGRU219D BARKSTON HEATH RWY 10 + 525756N 0003847W -
525827N 0003836W -
525813N 0003651W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525741N 0003655W -
525756N 0003847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6465194444,52.96551111109999,609.6 -0.6153789167,52.9613583333,609.6 -0.6153974861,52.964387462,609.6 -0.6149598521,52.96740506339999,609.6 -0.6140695278,52.9703861389,609.6 -0.6432944444000001,52.9742833333,609.6 -0.6465194444,52.96551111109999,609.6 + + + + +
+ + EGRU219E BARKSTON HEATH RWY 28 + 525709N 0002854W -
525638N 0002906W -
525651N 0003042W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525721N 0003023W -
525709N 0002854W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4816833333,52.9526333333,609.6 -0.5064422778,52.9559658056,609.6 -0.5077235244,52.9530372713,609.6 -0.509440117,52.95019118940001,609.6 -0.5115777500000001,52.9474511111,609.6 -0.4849027778,52.94386111110001,609.6 -0.4816833333,52.9526333333,609.6 + + + + +
+ + EGRU219F BARKSTON HEATH RWY 18 + 530037N 0003400W -
530038N 0003306W -
525945N 0003303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525946N 0003356W -
530037N 0003400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5665701111,53.01019069439999,609.6 -0.5656517222,52.9961111667,609.6 -0.5606649345,52.9962663366,609.6 -0.5556753315,52.9961485956,609.6 -0.5507238889,52.99575891670001,609.6 -0.5516831111,53.0105427222,609.6 -0.5665701111,53.01019069439999,609.6 + + + + +
+ + EGRU219G BARKSTON HEATH RWY 36 + 525449N 0003243W -
525448N 0003337W -
525547N 0003341W thence anti-clockwise by the arc of a circle radius 2 NM centred on 525747N 0003337W to
525551N 0003247W -
525449N 0003243W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.54540575,52.9136083333,609.6 -0.5465145,52.9307613889,609.6 -0.5513929375,52.9301394272,609.6 -0.5563443631,52.9297863492,609.6 -0.5613283056,52.9297050556,609.6 -0.5602594722000001,52.91325630560001,609.6 -0.54540575,52.9136083333,609.6 + + + + +
+ + EGRU220A WITTERING + A circle, 2.5 NM radius, centred at 523647N 0002833W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4759055555999999,52.6546625512,609.6 -0.4822183994000001,52.65448489570001,609.6 -0.4884772319,52.6539534489,609.6 -0.4946285077,52.6530727579,609.6 -0.5006196095,52.6518503568,609.6 -0.5063993013,52.6502967026,609.6 -0.5119181697,52.6484250848,609.6 -0.5171290495999999,52.64625151049999,609.6 -0.5219874283,52.6437945672,609.6 -0.5264518282,52.6410752618,609.6 -0.5304841608999999,52.6381168408,609.6 -0.5340500523,52.6349445897,609.6 -0.5371191351,52.631585616,609.6 -0.5396653057,52.6280686166,609.6 -0.5416669443,52.62442363110001,609.6 -0.5431070957,52.6206817852,609.6 -0.5439736099,52.6168750233,609.6 -0.5442592411,52.6130358359,609.6 -0.5439617044,52.6091969817,609.6 -0.54308369,52.6053912083,609.6 -0.5416328355,52.6016509723,609.6 -0.5396216554,52.5980081635,609.6 -0.5370674297,52.5944938332,609.6 -0.5339920525,52.5911379304,609.6 -0.5304218419,52.5879690473,609.6 -0.5263873122,52.58501417670001,609.6 -0.5219229123,52.5822984832,609.6 -0.5170667305,52.5798450902,609.6 -0.5118601699000001,52.5776748839,609.6 -0.5063475957,52.575806337,609.6 -0.5005759591,52.574255352,609.6 -0.4945943989,52.5730351276,609.6 -0.4884538261,52.5721560465,609.6 -0.4822064938,52.5716255882,609.6 -0.4759055555999999,52.5714482659,609.6 -0.4696046173,52.5716255882,609.6 -0.463357285,52.5721560465,609.6 -0.4572167122,52.5730351276,609.6 -0.4512351519999999,52.574255352,609.6 -0.4454635154000001,52.575806337,609.6 -0.4399509412,52.5776748839,609.6 -0.4347443806,52.5798450902,609.6 -0.4298881989,52.5822984832,609.6 -0.4254237989,52.58501417670001,609.6 -0.4213892692,52.5879690473,609.6 -0.4178190586,52.5911379304,609.6 -0.4147436814,52.5944938332,609.6 -0.4121894557,52.5980081635,609.6 -0.4101782756,52.6016509723,609.6 -0.4087274210999999,52.6053912083,609.6 -0.4078494068,52.6091969817,609.6 -0.40755187,52.6130358359,609.6 -0.4078375012,52.6168750233,609.6 -0.4087040154,52.6206817852,609.6 -0.4101441668,52.62442363110001,609.6 -0.4121458054,52.6280686166,609.6 -0.414691976,52.631585616,609.6 -0.4177610588,52.6349445897,609.6 -0.4213269502,52.6381168408,609.6 -0.4253592829,52.6410752618,609.6 -0.4298236828,52.6437945672,609.6 -0.4346820616,52.64625151049999,609.6 -0.4398929414,52.6484250848,609.6 -0.4454118097999999,52.6502967026,609.6 -0.4511915016,52.6518503568,609.6 -0.4571826034,52.6530727579,609.6 -0.4633338792000001,52.6539534489,609.6 -0.4695927117,52.65448489570001,609.6 -0.4759055555999999,52.6546625512,609.6 + + + + +
+ + EGRU220B WITTERING RWY 07 + 523532N 0003349W -
523603N 0003404W -
523619N 0003235W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to
523548N 0003220W -
523532N 0003349W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5636166667,52.5921861111,609.6 -0.5387953333,52.5967718611,609.6 -0.5405613037,52.5995733524,609.6 -0.5419912752,52.60244504039999,609.6 -0.54307775,52.605372,609.6 -0.5678833333,52.60078888889999,609.6 -0.5636166667,52.5921861111,609.6 + + + + +
+ + EGRU220C WITTERING RWY 25 + 523802N 0002317W -
523731N 0002302W -
523715N 0002431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523647N 0002833W to
523746N 0002447W -
523802N 0002317W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3881305556,52.6338611111,609.6 -0.4129719444,52.6293098333,609.6 -0.4112122551,52.6265062386,609.6 -0.4097894559999999,52.6236327327,609.6 -0.4087108889000001,52.6207042778,609.6 -0.3838527778,52.6252583333,609.6 -0.3881305556,52.6338611111,609.6 + + + + +
+ + EGRU222A OLD WARDEN + A circle, 2 NM radius, centred at 520512N 0001907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3186111111,52.1199552691,609.6 -0.3241713908,52.1197787048,609.6 -0.3296725996,52.1192508877,609.6 -0.3350562982,52.11837742500001,609.6 -0.3402653038,52.1171675954,609.6 -0.3452443011,52.1156342498,609.6 -0.3499404329,52.1137936743,609.6 -0.3543038634,52.1116654157,609.6 -0.3582883093,52.1092720731,609.6 -0.3618515313,52.1066390567,609.6 -0.364955782,52.10379431650001,609.6 -0.3675682054,52.1007680445,609.6 -0.3696611824,52.0975923532,609.6 -0.3712126211,52.0943009337,609.6 -0.3722061867000001,52.0909286972,609.6 -0.3726314698,52.08751140439999,609.6 -0.3724840918,52.0840852855,609.6 -0.3717657458,52.0806866562,609.6 -0.3704841729,52.0773515323,609.6 -0.3686530753,52.07411524919999,609.6 -0.3662919654,52.07101208730001,609.6 -0.3634259553,52.0680749102,609.6 -0.3600854865,52.06533481739999,609.6 -0.3563060054,52.062820816,609.6 -0.3521275850999999,52.0605595152,609.6 -0.347594501,52.05857484580001,609.6 -0.3427547618,52.056887808,609.6 -0.3376596025,52.05551625049999,609.6 -0.3323629441,52.0544746828,609.6 -0.326920826,52.05377412280001,609.6 -0.3213908161,52.0534219804,609.6 -0.3158314061,52.0534219804,609.6 -0.3103013962,52.05377412280001,609.6 -0.3048592781,52.0544746828,609.6 -0.2995626198,52.05551625049999,609.6 -0.2944674604,52.056887808,609.6 -0.2896277212,52.05857484580001,609.6 -0.2850946371,52.0605595152,609.6 -0.2809162168,52.062820816,609.6 -0.2771367357,52.06533481739999,609.6 -0.273796267,52.0680749102,609.6 -0.2709302568,52.07101208730001,609.6 -0.2685691469,52.07411524919999,609.6 -0.2667380493,52.0773515323,609.6 -0.2654564765,52.0806866562,609.6 -0.2647381305,52.0840852855,609.6 -0.2645907525,52.08751140439999,609.6 -0.2650160355,52.0909286972,609.6 -0.2660096011,52.0943009337,609.6 -0.2675610398,52.0975923532,609.6 -0.2696540168,52.1007680445,609.6 -0.2722664402,52.10379431650001,609.6 -0.2753706909,52.1066390567,609.6 -0.2789339129,52.1092720731,609.6 -0.2829183588,52.1116654157,609.6 -0.2872817893,52.1137936743,609.6 -0.2919779211,52.1156342498,609.6 -0.2969569184,52.1171675954,609.6 -0.302165924,52.11837742500001,609.6 -0.3075496226,52.1192508877,609.6 -0.3130508314,52.1197787048,609.6 -0.3186111111,52.1199552691,609.6 + + + + +
+ + EGRU222B OLD WARDEN RWY 03 + 520232N 0002041W -
520245N 0002128W -
520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520318N 0002006W -
520232N 0002041W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3446666667,52.0421166667,609.6 -0.3348690556,52.0549213889,609.6 -0.3394451207,52.0559533739,609.6 -0.3438518961,52.057235281,609.6 -0.3480535556,52.0587566944,609.6 -0.3578472222,52.0459527778,609.6 -0.3446666667,52.0421166667,609.6 + + + + +
+ + EGRU222C OLD WARDEN RWY 21 + 520753N 0001732W -
520739N 0001645W -
520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520706N 0001808W -
520753N 0001732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2923277778,52.1314555556,609.6 -0.3023411667,52.1184116944,609.6 -0.2977597768,52.11737904,609.6 -0.2933484744,52.11609621729999,609.6 -0.2891432222,52.1145736944,609.6 -0.279125,52.1276194444,609.6 -0.2923277778,52.1314555556,609.6 + + + + +
+ + EGRU222D OLD WARDEN RWY 03X + 520218N 0002051W -
520231N 0002139W -
520332N 0002053W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520318N 0002005W -
520218N 0002051W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3476277778,52.03821666670001,609.6 -0.3348561389,52.0549188611,609.6 -0.339432504,52.05595012949999,609.6 -0.3438396998,52.05723131520001,609.6 -0.3480418889,52.0587520278,609.6 -0.3608055556,52.0420527778,609.6 -0.3476277778,52.03821666670001,609.6 + + + + +
+ + EGRU222E OLD WARDEN RWY 21X + 520753N 0001732W -
520739N 0001645W -
520652N 0001721W thence anti-clockwise by the arc of a circle radius 2 NM centred on 520512N 0001907W to
520706N 0001808W -
520753N 0001732W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2923444444,52.13146111109999,609.6 -0.3023537222,52.1184141389,609.6 -0.2977706736,52.1173818267,609.6 -0.2933577082,52.1160992039,609.6 -0.2891508333,52.1145767222,609.6 -0.2791361111,52.127625,609.6 -0.2923444444,52.13146111109999,609.6 + + + + +
+ + EGRU223A PETERBOROUGH/CONINGTON + A circle, 2 NM radius, centred at 522805N 0001503W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2509305556,52.5013558845,609.6 -0.2565388288,52.5011793299,609.6 -0.2620875194,52.50065154170001,609.6 -0.2675176819,52.499778127,609.6 -0.2727716385,52.49856836429999,609.6 -0.2777935952,52.4970351043,609.6 -0.2825302375,52.4951946324,609.6 -0.286931299,52.49306649479999,609.6 -0.2909500969,52.4906732901,609.6 -0.2945440276,52.4880404274,609.6 -0.2976750187,52.48519585559999,609.6 -0.3003099319,52.48216976560001,609.6 -0.3024209115,52.4789942684,609.6 -0.3039856767,52.4757030532,609.6 -0.3049877539,52.4723310297,609.6 -0.3054166464,52.4689139562,609.6 -0.3052679403,52.4654880608,609.6 -0.3045433456,52.46208965680001,609.6 -0.3032506726,52.45875475750001,609.6 -0.3014037436,52.4555186956,609.6 -0.2990222414,52.45241574890001,609.6 -0.2961314959,52.4494787782,609.6 -0.2927622124,52.4467388803,609.6 -0.2889501434,52.44422505979999,609.6 -0.2847357077,52.4419639235,609.6 -0.2801635622,52.43997939970001,609.6 -0.2752821285,52.4382924865,609.6 -0.2701430821,52.4369210311,609.6 -0.2648008074,52.4358795413,609.6 -0.2593118247,52.43517903379999,609.6 -0.2537341961,52.43482691799999,609.6 -0.248126915,52.43482691799999,609.6 -0.2425492865,52.43517903379999,609.6 -0.2370603038,52.4358795413,609.6 -0.231718029,52.4369210311,609.6 -0.2265789826,52.4382924865,609.6 -0.221697549,52.43997939970001,609.6 -0.2171254034,52.4419639235,609.6 -0.2129109677,52.44422505979999,609.6 -0.2090988987,52.4467388803,609.6 -0.2057296152,52.4494787782,609.6 -0.2028388697,52.45241574890001,609.6 -0.2004573675,52.4555186956,609.6 -0.1986104385,52.45875475750001,609.6 -0.1973177656,52.46208965680001,609.6 -0.1965931708,52.4654880608,609.6 -0.1964444647,52.4689139562,609.6 -0.1968733572,52.4723310297,609.6 -0.1978754344,52.4757030532,609.6 -0.1994401997,52.4789942684,609.6 -0.2015511792,52.48216976560001,609.6 -0.2041860924,52.48519585559999,609.6 -0.2073170836,52.4880404274,609.6 -0.2109110142,52.4906732901,609.6 -0.2149298121,52.49306649479999,609.6 -0.2193308736,52.4951946324,609.6 -0.2240675159,52.4970351043,609.6 -0.2290894726,52.49856836429999,609.6 -0.2343434292,52.499778127,609.6 -0.2397735918,52.50065154170001,609.6 -0.2453222823,52.5011793299,609.6 -0.2509305556,52.5013558845,609.6 + + + + +
+ + EGRU223B PETERBOROUGH/CONINGTON RWY 10 + 522803N 0001956W -
522835N 0001952W -
522830N 0001815W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to
522758N 0001819W -
522803N 0001956W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3321527778,52.4673944444,609.6 -0.3053404444,52.46613588890001,609.6 -0.3054061395,52.4691397138,609.6 -0.3050281085,52.4721349212,609.6 -0.3042093333,52.4750971111,609.6 -0.3310083333,52.4763555556,609.6 -0.3321527778,52.4673944444,609.6 + + + + +
+ + EGRU223C PETERBOROUGH/CONINGTON RWY 28 + 522808N 0001017W -
522735N 0001021W -
522740N 0001152W thence anti-clockwise by the arc of a circle radius 2 NM centred on 522805N 0001503W to
522812N 0001147W -
522808N 0001017W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1714472222,52.4687722222,609.6 -0.1965159444,52.4699780556,609.6 -0.1964576045,52.46697486480001,609.6 -0.1968427065,52.4639806853,609.6 -0.1976680278,52.4610198889,609.6 -0.1725861111,52.4598138889,609.6 -0.1714472222,52.4687722222,609.6 + + + + +
+ + EGRU224A FENLAND + A circle, 2 NM radius, centred at 524422N 0000148W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0298666667,52.7727293506,609.6 -0.0355097506,52.7725528028,609.6 -0.0410928807,52.7720250351,609.6 -0.0465567445,52.7711516544,609.6 -0.05184330499999999,52.769941939,609.6 -0.0568964209,52.76840873939999,609.6 -0.0616624461,52.7665683408,609.6 -0.0660908021,52.76444028889999,609.6 -0.07013451580000001,52.7620471818,609.6 -0.0737507198,52.7594144279,609.6 -0.076901106,52.7565699754,609.6 -0.0795523311,52.7535440143,609.6 -0.0816763678,52.7503686545,609.6 -0.0832507985,52.74707758429999,609.6 -0.084259049,52.7437057116,609.6 -0.084690559,52.7402887937,609.6 -0.0845408891,52.7368630569,609.6 -0.0838117617,52.7334648127,609.6 -0.08251103730000001,52.7301300729,609.6 -0.0806526253,52.726894168,609.6 -0.078256332,52.7237913741,609.6 -0.0753476454,52.7208545501,609.6 -0.07195746209999999,52.7181147907,609.6 -0.06812175669999999,52.7156010987,609.6 -0.0638811987,52.7133400792,609.6 -0.0592807215,52.7113556589,609.6 -0.05436904649999999,52.7096688344,609.6 -0.04919816859999999,52.70829745149999,609.6 -0.0438228081,52.7072560171,609.6 -0.0382998343,52.70655554699999,609.6 -0.0326876677,52.70620345,609.6 -0.0270456657,52.70620345,609.6 -0.021433499,52.70655554699999,609.6 -0.0159105253,52.7072560171,609.6 -0.0105351647,52.70829745149999,609.6 -0.0053642868,52.7096688344,609.6 -0.0004526119,52.7113556589,609.6 0.0041478653,52.7133400792,609.6 0.0083884233,52.7156010987,609.6 0.0122241288,52.7181147907,609.6 0.0156143121,52.7208545501,609.6 0.0185229986,52.7237913741,609.6 0.020919292,52.726894168,609.6 0.0227777039,52.7301300729,609.6 0.0240784284,52.7334648127,609.6 0.0248075558,52.7368630569,609.6 0.0249572257,52.7402887937,609.6 0.0245257156,52.7437057116,609.6 0.0235174651,52.74707758429999,609.6 0.0219430344,52.7503686545,609.6 0.0198189978,52.7535440143,609.6 0.0171677727,52.7565699754,609.6 0.0140173865,52.7594144279,609.6 0.0104011825,52.7620471818,609.6 0.0063574687,52.76444028889999,609.6 0.0019291128,52.7665683408,609.6 -0.0028369125,52.76840873939999,609.6 -0.007890028300000001,52.769941939,609.6 -0.0131765888,52.7711516544,609.6 -0.0186404526,52.7720250351,609.6 -0.0242235827,52.7725528028,609.6 -0.0298666667,52.7727293506,609.6 + + + + +
+ + EGRU224B FENLAND RWY 18 + 524711N 0000210W -
524710N 0000116W -
524620N 0000118W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to
524621N 0000211W -
524711N 0000210W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.03605,52.7863611111,609.6 -0.0364105278,52.7724917222,609.6 -0.0314710385,52.7727151248,609.6 -0.0265184494,52.77266731539999,609.6 -0.0215931944,52.7723486944,609.6 -0.0212277778,52.7862166667,609.6 -0.03605,52.7863611111,609.6 + + + + +
+ + EGRU224C FENLAND RWY 36 + 524130N 0000125W -
524131N 0000219W -
524224N 0000217W thence anti-clockwise by the arc of a circle radius 2 NM centred on 524422N 0000148W to
524223N 0000124W -
524130N 0000125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0237138889,52.6916888889,609.6 -0.0233277778,52.7063969722,609.6 -0.0282594659,52.7061736718,609.6 -0.0332042095,52.70622110830001,609.6 -0.0381218333,52.7065389167,609.6 -0.0385027778,52.6918305556,609.6 -0.0237138889,52.6916888889,609.6 + + + + +
+ + EGRU225A DUXFORD + A circle, 2 NM radius, centred at 520526N 0000753E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1315027778,52.123808025,609.6 0.1259420186,52.1236314608,609.6 0.1204403355,52.123103644,609.6 0.1150561727,52.12223018179999,609.6 0.109846718,52.1210203528,609.6 0.1048672915,52.11948700819999,609.6 0.1001707551,52.1176464337,609.6 0.0958069486,52.1155181763,609.6 0.0918221595,52.1131248351,609.6 0.08825863069999998,52.11049182030001,609.6 0.0851541128,52.1076470817,609.6 0.08254146480000001,52.10462081160001,609.6 0.0804483079,52.1014451223,609.6 0.0788967361,52.0981537048,609.6 0.0779030855,52.0947814705,609.6 0.0774777663,52.0913641799,609.6 0.07762515759999999,52.0879380633,609.6 0.078343566,52.0845394362,609.6 0.07962524980000001,52.08120431460001,609.6 0.0814565055,52.0779680338,609.6 0.0838178192,52.0748648741,609.6 0.0866840764,52.0719276991,609.6 0.09002483299999998,52.06918760819999,609.6 0.0938046397,52.0666736086,609.6 0.0979834198,52.0644123095,609.6 0.1025168941,52.0624276416,609.6 0.1073570499,52.06074060499999,609.6 0.1124526477,52.0593690485,609.6 0.1177497618,52.05832748169999,609.6 0.1231923481,52.0576269221,609.6 0.1287228336,52.0572747801,609.6 0.1342827219,52.0572747801,609.6 0.1398132075,52.0576269221,609.6 0.1452557938,52.05832748169999,609.6 0.1505529079,52.0593690485,609.6 0.1556485057,52.06074060499999,609.6 0.1604886614,52.0624276416,609.6 0.1650221357,52.0644123095,609.6 0.1692009158,52.0666736086,609.6 0.1729807226,52.06918760819999,609.6 0.1763214791,52.0719276991,609.6 0.1791877364,52.0748648741,609.6 0.18154905,52.0779680338,609.6 0.1833803058,52.08120431460001,609.6 0.1846619895,52.0845394362,609.6 0.1853803979,52.0879380633,609.6 0.1855277892,52.0913641799,609.6 0.1851024701,52.0947814705,609.6 0.1841088195,52.0981537048,609.6 0.1825572476,52.1014451223,609.6 0.1804640907,52.10462081160001,609.6 0.1778514427,52.1076470817,609.6 0.1747469248,52.11049182030001,609.6 0.1711833961,52.1131248351,609.6 0.167198607,52.1155181763,609.6 0.1628348005,52.1176464337,609.6 0.158138264,52.11948700819999,609.6 0.1531588375,52.1210203528,609.6 0.1479493829,52.12223018179999,609.6 0.1425652201,52.123103644,609.6 0.137063537,52.1236314608,609.6 0.1315027778,52.123808025,609.6 + + + + +
+ + EGRU225B DUXFORD RWY 06L + 520342N 0000358E -
520409N 0000331E -
520441N 0000453E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520413N 0000519E -
520342N 0000358E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0662027778,52.0616638889,609.6 0.0885908611,52.0702925556,609.6 0.0858030761,52.07276003560001,609.6 0.08338763709999999,52.07537239800001,609.6 0.08136430560000001,52.0781083611,609.6 0.0584833333,52.0692888889,609.6 0.0662027778,52.0616638889,609.6 + + + + +
+ + EGRU225C DUXFORD RWY 24R + 520716N 0001135E -
520648N 0001203E -
520619N 0001047E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520646N 0001018E -
520716N 0001135E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1931527778,52.1210833333,609.6 0.1716298056,52.1128239167,609.6 0.1747339861,52.1105024373,609.6 0.177484965,52.10801790679999,609.6 0.1798603056,52.1053906111,609.6 0.2008861111,52.1134583333,609.6 0.1931527778,52.1210833333,609.6 + + + + +
+ + EGRU225D DUXFORD RWY 06R + 520334N 0000352E -
520401N 0000325E -
520437N 0000456E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520409N 0000524E -
520334N 0000352E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.06455875,52.05945183330001,609.6 0.08995541669999998,52.06923894439999,609.6 0.08701042639999999,52.0716326258,609.6 0.0844272855,52.07418010829999,609.6 0.0822270556,52.0768606667,609.6 0.0568375833,52.0670756667,609.6 0.06455875,52.05945183330001,609.6 + + + + +
+ + EGRU225E DUXFORD RWY 24L + 520716N 0001150E -
520648N 0001218E -
520615N 0001051E thence anti-clockwise by the arc of a circle radius 2 NM centred on 520526N 0000753E to
520642N 0001023E -
520716N 0001150E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1973161944,52.1210931389,609.6 0.1730776667,52.1117941389,609.6 0.1760220254,52.1093989495,609.6 0.1786034196,52.1068500334,609.6 0.1808008611,52.1041681667,609.6 0.2050466944,52.11346938890001,609.6 0.1973161944,52.1210931389,609.6 + + + + +
+ + EGRU226A CAMBRIDGE + A circle, 2.5 NM radius, centred at 521218N 0001030E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.175,52.2466098839,609.6 0.1687452292,52.2464322185,609.6 0.1625439707,52.2459007422,609.6 0.1564492751,52.2450200018,609.6 0.1505132739,52.2437975319,609.6 0.1447867299,52.2422437896,609.6 0.1393186007,52.2403720645,609.6 0.1341556167,52.2381983642,609.6 0.1293418805,52.2357412764,609.6 0.1249184884,52.2330218089,609.6 0.1209231787,52.23006320870001,609.6 0.1173900105,52.2268907621,609.6 0.1143490731,52.2235315779,609.6 0.111826232,52.2200143539,609.6 0.1098429104,52.2163691314,609.6 0.10841591,52.2126270374,609.6 0.1075572719,52.2088200185,609.6 0.1072741782,52.2049805669,609.6 0.1075688958,52.2011414438,609.6 0.108438762,52.1973353987,609.6 0.1098762123,52.1935948911,609.6 0.1118688498,52.1899518133,609.6 0.1143995555,52.1864372194,609.6 0.1174466383,52.18308106089999,609.6 0.1209840236,52.179911933,609.6 0.1249814783,52.176956831,609.6 0.1294048705,52.1742409224,609.6 0.1342164617,52.1717873329,609.6 0.1393752286,52.1696169512,609.6 0.1448372124,52.1677482519,609.6 0.1505558918,52.1661971396,609.6 0.1564825772,52.1649768144,609.6 0.1625668229,52.16409766040001,609.6 0.1687568532,52.163567158,609.6 0.175,52.163389821,609.6 0.1812431468,52.163567158,609.6 0.1874331771,52.16409766040001,609.6 0.1935174228,52.1649768144,609.6 0.1994441082,52.1661971396,609.6 0.2051627876,52.1677482519,609.6 0.2106247714,52.1696169512,609.6 0.2157835383,52.1717873329,609.6 0.2205951295,52.1742409224,609.6 0.2250185217,52.176956831,609.6 0.2290159764,52.179911933,609.6 0.2325533617,52.18308106089999,609.6 0.2356004445,52.1864372194,609.6 0.2381311502,52.1899518133,609.6 0.2401237877,52.1935948911,609.6 0.241561238,52.1973353987,609.6 0.2424311042,52.2011414438,609.6 0.2427258218,52.2049805669,609.6 0.2424427281,52.2088200185,609.6 0.24158409,52.2126270374,609.6 0.2401570896,52.2163691314,609.6 0.238173768,52.2200143539,609.6 0.2356509269,52.2235315779,609.6 0.2326099895,52.2268907621,609.6 0.2290768213,52.23006320870001,609.6 0.2250815116,52.2330218089,609.6 0.2206581195,52.2357412764,609.6 0.2158443833,52.2381983642,609.6 0.2106813993,52.2403720645,609.6 0.2052132701,52.2422437896,609.6 0.1994867261,52.2437975319,609.6 0.1935507249,52.2450200018,609.6 0.1874560293,52.2459007422,609.6 0.1812547708,52.2464322185,609.6 0.175,52.2466098839,609.6 + + + + +
+ + EGRU226B CAMBRIDGE RWY 05 + 521006N 0000655E -
521030N 0000621E -
521055N 0000708E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521030N 0000742E -
521006N 0000655E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1152138889,52.1682055556,609.6 0.1281993889,52.1749323889,609.6 0.1247950609,52.1770828876,609.6 0.1216513551,52.17937854459999,609.6 0.1187846389,52.1818074444,609.6 0.1058055556,52.1750833333,609.6 0.1152138889,52.1682055556,609.6 + + + + +
+ + EGRU226C CAMBRIDGE RWY 23 + 521432N 0001409E -
521407N 0001442E -
521341N 0001352E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521406N 0001319E -
521432N 0001409E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2357,52.24222222220001,609.6 0.2218291389,52.23506925,609.6 0.2252353881,52.2329176763,609.6 0.2283799158,52.2306208904,609.6 0.2312463889,52.2281908611,609.6 0.245125,52.2353472222,609.6 0.2357,52.24222222220001,609.6 + + + + +
+ + EGRU226D CAMBRIDGE RWY 05G + 521015N 0000728E -
521039N 0000654E -
521049N 0000713E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521026N 0000749E -
521015N 0000728E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1243861111,52.1707,609.6 0.13028475,52.1737569444,609.6 0.1267348617,52.1758197269,609.6 0.1234358833,52.17803445490001,609.6 0.120405,52.1803896111,609.6 0.114975,52.177575,609.6 0.1243861111,52.1707,609.6 + + + + +
+ + EGRU226E CAMBRIDGE RWY 23G + 521426N 0001413E -
521402N 0001447E -
521336N 0001358E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 521218N 0001030E to
521402N 0001326E -
521426N 0001413E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2369527778,52.2406555556,609.6 0.2237949167,52.2338656944,609.6 0.2270582421,52.2316275242,609.6 0.2300497493,52.22925054540001,609.6 0.2327538611,52.22674716669999,609.6 0.2463805556,52.2337777778,609.6 0.2369527778,52.2406555556,609.6 + + + + +
+ + EGRU227A MILDENHALL + A circle, 2.5 NM radius, centred at 522143N 0002911E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4864055555999999,52.40354210509999,609.6 0.4801286155,52.4033644435,609.6 0.4739053782,52.40283297860001,609.6 0.4677890832,52.40195225730001,609.6 0.4618320474,52.4007298139,609.6 0.4560852142999999,52.39917610559999,609.6 0.4505977154,52.39730442180001,609.6 0.4454164473,52.39513077019999,609.6 0.4405856688,52.39267373810001,609.6 0.4361466218999999,52.389954333,609.6 0.4321371786,52.38699580189999,609.6 0.4285915182,52.38382343070001,609.6 0.4255398363,52.38046432760001,609.6 0.423008089,52.3769471901,609.6 0.4210177748,52.3733020589,609.6 0.4195857539,52.3695600605,609.6 0.4187241089,52.36575314049999,609.6 0.4184400464,52.3619137907,609.6 0.4187358401,52.35807477110001,609.6 0.4196088168,52.3542688306,609.6 0.421051384,52.35052842750001,609.6 0.4230511001,52.3468854532,609.6 0.4255907844,52.3433709608,609.6 0.4286486685,52.3400149007,609.6 0.4321985849,52.336845867,609.6 0.4362101930000001,52.333890854,609.6 0.4406492399,52.3311750281,609.6 0.4454778536,52.3287215143,609.6 0.4506548658,52.3265512,609.6 0.4561361626,52.3246825593,609.6 0.4618750585,52.323131496,609.6 0.4678226925,52.3219112096,609.6 0.4739284412000001,52.32103208360001,609.6 0.4801403466999999,52.3205015982,609.6 0.4864055555999999,52.32032426680001,609.6 0.4926707644,52.3205015982,609.6 0.4988826699,52.32103208360001,609.6 0.5049884186,52.3219112096,609.6 0.5109360526,52.323131496,609.6 0.5166749486,52.3246825593,609.6 0.5221562453,52.3265512,609.6 0.5273332576,52.3287215143,609.6 0.5321618712,52.3311750281,609.6 0.5366009181,52.333890854,609.6 0.5406125262,52.336845867,609.6 0.5441624426,52.3400149007,609.6 0.5472203267,52.3433709608,609.6 0.5497600110999999,52.3468854532,609.6 0.5517597271,52.35052842750001,609.6 0.5532022944,52.3542688306,609.6 0.554075271,52.35807477110001,609.6 0.5543710647,52.3619137907,609.6 0.5540870022,52.36575314049999,609.6 0.5532253572,52.3695600605,609.6 0.5517933363,52.3733020589,609.6 0.5498030221,52.3769471901,609.6 0.5472712748,52.38046432760001,609.6 0.5442195929,52.38382343070001,609.6 0.5406739325,52.38699580189999,609.6 0.5366644892,52.389954333,609.6 0.5322254424,52.39267373810001,609.6 0.5273946639,52.39513077019999,609.6 0.5222133957,52.39730442180001,609.6 0.5167258968,52.39917610559999,609.6 0.5109790637,52.4007298139,609.6 0.5050220278999999,52.40195225730001,609.6 0.4989057329,52.40283297860001,609.6 0.4926824956,52.4033644435,609.6 0.4864055555999999,52.40354210509999,609.6 + + + + +
+ + EGRU227B MILDENHALL RWY 11 + 522215N 0002335E -
522246N 0002348E -
522233N 0002520E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to
522201N 0002508E -
522215N 0002335E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3931852499999999,52.37075433329999,609.6 0.41895225,52.3670513611,609.6 0.4197280497,52.3700143536,609.6 0.420850861,52.3729354022,609.6 0.4223148889,52.3757993056,609.6 0.39655725,52.37950097220001,609.6 0.3931852499999999,52.37075433329999,609.6 + + + + +
+ + EGRU227C MILDENHALL RWY 29 + 522111N 0003446E -
522040N 0003434E -
522053N 0003302E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522143N 0002911E to
522124N 0003314E -
522111N 0003446E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5795797222,52.3530635,609.6 0.5538478610999999,52.3567994722,609.6 0.5530659598,52.3538371034,609.6 0.5519375386000001,52.3509169327,609.6 0.5504685278,52.3480541389,609.6 0.5762097222,52.3443168611,609.6 0.5795797222,52.3530635,609.6 + + + + +
+ + EGRU228A MARHAM + A circle, 2.5 NM radius, centred at 523854N 0003302E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5505555556,52.68994007980001,609.6 0.5442376252,52.6897624251,609.6 0.5379737499,52.6892309809,609.6 0.5318175182,52.68835029409999,609.6 0.5258215902,52.6871278989,609.6 0.5200372433,52.6855742523,609.6 0.5145139307,52.68370264370001,609.6 0.5092988557,52.6815290804,609.6 0.5044365668,52.6790721494,609.6 0.4999685750999999,52.67635285800001,609.6 0.4959329997,52.6733944524,609.6 0.4923642421,52.6702222182,609.6 0.4892926942,52.6668632627,609.6 0.4867444802,52.66334628249999,609.6 0.4847412373000001,52.6597013175,609.6 0.4832999341,52.655959493,609.6 0.4824327301,52.6521527532,609.6 0.4821468767,52.6483135886,609.6 0.4824446604,52.6444747577,609.6 0.4833233885,52.6406690077,609.6 0.4847754171,52.6369287951,609.6 0.4867882214,52.6332860095,609.6 0.4893445071999999,52.629771702,609.6 0.4924223626,52.6264158213,609.6 0.4959954484,52.6232469594,609.6 0.5000332253999999,52.6202921087,609.6 0.5045012171,52.6175764338,609.6 0.5093613044999999,52.6151230578,609.6 0.5145720512,52.6129528667,609.6 0.5200890564,52.61108433289999,609.6 0.5258653315,52.609533359,609.6 0.531851698,52.6083131433,609.6 0.5379972043,52.6074340684,609.6 0.5442495556,52.606903614,609.6 0.5505555556,52.606726293,609.6 0.5568615555999999,52.606903614,609.6 0.5631139068,52.6074340684,609.6 0.5692594130999999,52.6083131433,609.6 0.5752457796,52.609533359,609.6 0.5810220547,52.61108433289999,609.6 0.5865390599,52.6129528667,609.6 0.5917498066,52.6151230578,609.6 0.596609894,52.6175764338,609.6 0.6010778857,52.6202921087,609.6 0.6051156626999999,52.6232469594,609.6 0.6086887485,52.6264158213,609.6 0.6117666039,52.629771702,609.6 0.6143228897,52.6332860095,609.6 0.616335694,52.6369287951,609.6 0.6177877226,52.6406690077,609.6 0.6186664507,52.6444747577,609.6 0.6189642344,52.6483135886,609.6 0.6186783810000001,52.6521527532,609.6 0.617811177,52.655959493,609.6 0.6163698738,52.6597013175,609.6 0.6143666309,52.66334628249999,609.6 0.6118184169999999,52.6668632627,609.6 0.608746869,52.6702222182,609.6 0.6051781114,52.6733944524,609.6 0.601142536,52.67635285800001,609.6 0.5966745443,52.6790721494,609.6 0.5918122554,52.6815290804,609.6 0.5865971804,52.68370264370001,609.6 0.5810738678,52.6855742523,609.6 0.5752895209,52.6871278989,609.6 0.5692935929,52.68835029409999,609.6 0.5631373613,52.6892309809,609.6 0.5568734859,52.6897624251,609.6 0.5505555556,52.68994007980001,609.6 + + + + +
+ + EGRU228B MARHAM RWY 01 + 523538N 0003307E -
523543N 0003215E -
523626N 0003225E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
523625N 0003319E -
523538N 0003307E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5520111111,52.5939194444,609.6 0.5552008333,52.6068224167,609.6 0.5502455031,52.60672673409999,609.6 0.5452918019,52.60684977660001,609.6 0.5403657222,52.60719091669999,609.6 0.5374194444,52.5952555556,609.6 0.5520111111,52.5939194444,609.6 + + + + +
+ + EGRU228C MARHAM RWY 19 + 524200N 0003348E -
524156N 0003441E -
524114N 0003430E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
524122N 0003339E -
524200N 0003348E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5633555555999999,52.70009722219999,609.6 0.5607228889,52.6894784167,609.6 0.5656053044,52.68892168020001,609.6 0.5704082912,52.6881511361,609.6 0.5751065,52.68717083330001,609.6 0.5779833333,52.6987583333,609.6 0.5633555555999999,52.70009722219999,609.6 + + + + +
+ + EGRU228D MARHAM RWY 06 + 523643N 0002837E -
523710N 0002807E -
523743N 0002925E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
523716N 0002956E -
523643N 0002837E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.476925,52.6119888889,609.6 0.4987624167,52.62116350000001,609.6 0.4956781358,52.6235043234,609.6 0.4928787707,52.6259742675,609.6 0.4903788889,52.6285605,609.6 0.46855,52.6193888889,609.6 0.476925,52.6119888889,609.6 + + + + +
+ + EGRU228E MARHAM RWY 24 + 524104N 0003727E -
524038N 0003757E -
524005N 0003639E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 523854N 0003302E to
524032N 0003609E -
524104N 0003727E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6240777778,52.6845638889,609.6 0.6023875,52.6754983333,609.6 0.6054717452,52.6731559687,609.6 0.6082699432000001,52.6706845186,609.6 0.6107675833,52.6680968611,609.6 0.6324694444,52.6771666667,609.6 0.6240777778,52.6845638889,609.6 + + + + +
+ + EGRU229A LAKENHEATH + A circle, 2.5 NM radius, centred at 522434N 0003340E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5610111111,52.4510112135,609.6 0.5547274249,52.450833553,609.6 0.5484974994,52.4503020916,609.6 0.5423746316,52.44942137599999,609.6 0.5364111949,52.44819894060001,609.6 0.5306581878,52.4466452426,609.6 0.5251647946,52.44477357129999,609.6 0.5199779624999999,52.4425999343,609.6 0.515141998,52.440142919,609.6 0.5106981873999999,52.4374235329,609.6 0.5066844433,52.43446502259999,609.6 0.5031349815,52.43129267409999,609.6 0.5000800299,52.4279335955,609.6 0.4975455726,52.4244164841,609.6 0.4955531305,52.42077138050001,609.6 0.4941195817999999,52.417029411,609.6 0.4932570219,52.4132225209,609.6 0.4929726646,52.4093832018,609.6 0.4932687858,52.40554421350001,609.6 0.494142709,52.4017383046,609.6 0.4955868333999999,52.3979979332,609.6 0.4975887035,52.39435499020001,609.6 0.5001311201,52.39084052839999,609.6 0.5031922911,52.3874844981,609.6 0.5067460207,52.3843154928,609.6 0.5107619356999999,52.38136050679999,609.6 0.5152057463,52.3786447059,609.6 0.52003954,52.3761912149,609.6 0.5252221043,52.3740209211,609.6 0.530709278,52.3721522981,609.6 0.5364543259,52.3706012496,609.6 0.5424083345,52.3693809749,609.6 0.5485206266,52.3685018574,609.6 0.5547391887999999,52.3679713771,609.6 0.5610111111,52.36779404749999,609.6 0.5672830334,52.3679713771,609.6 0.5735015956,52.3685018574,609.6 0.5796138877,52.3693809749,609.6 0.5855678964,52.3706012496,609.6 0.5913129442,52.3721522981,609.6 0.5968001179,52.3740209211,609.6 0.6019826822,52.3761912149,609.6 0.6068164759,52.3786447059,609.6 0.6112602866,52.38136050679999,609.6 0.6152762015,52.3843154928,609.6 0.6188299311,52.3874844981,609.6 0.6218911021,52.39084052839999,609.6 0.6244335187,52.39435499020001,609.6 0.6264353888,52.3979979332,609.6 0.6278795132,52.4017383046,609.6 0.6287534364,52.40554421350001,609.6 0.6290495576,52.4093832018,609.6 0.6287652003,52.4132225209,609.6 0.6279026404,52.417029411,609.6 0.6264690917,52.42077138050001,609.6 0.6244766497000001,52.4244164841,609.6 0.6219421923,52.4279335955,609.6 0.6188872407,52.43129267409999,609.6 0.615337779,52.43446502259999,609.6 0.6113240349,52.4374235329,609.6 0.6068802242,52.440142919,609.6 0.6020442597,52.4425999343,609.6 0.5968574276,52.44477357129999,609.6 0.5913640344,52.4466452426,609.6 0.5856110273,52.44819894060001,609.6 0.5796475906,52.44942137599999,609.6 0.5735247228,52.4503020916,609.6 0.5672947973,52.450833553,609.6 0.5610111111,52.4510112135,609.6 + + + + +
+ + EGRU229B LAKENHEATH RWY 06 + 522224N 0002916E -
522251N 0002847E -
522323N 0003004E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to
522257N 0003034E -
522224N 0002916E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4878663333,52.3733966389,609.6 0.5093056111000001,52.38236897220001,609.6 0.5062544483,52.38471822310001,609.6 0.5034876038,52.3871958535,609.6 0.5010195,52.389789,609.6 0.4795878056,52.3808191667,609.6 0.4878663333,52.3733966389,609.6 + + + + +
+ + EGRU229C LAKENHEATH RWY 24 + 522643N 0003803E -
522617N 0003833E -
522544N 0003716E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 522434N 0003340E to
522611N 0003646E -
522643N 0003803E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6342404722,52.4453773611,609.6 0.6127547778,52.43643177780001,609.6 0.6158060476,52.43408086629999,609.6 0.6185718298,52.4316015868,609.6 0.6210377778,52.42900686109999,609.6 0.6425311111000001,52.4379549167,609.6 0.6342404722,52.4453773611,609.6 + + + + +
+ + EGRU230A WATTISHAM + A circle, 2.5 NM radius, centred at 520737N 0005719E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9554138889,52.1686382148,609.6 0.9491700573,52.16846054749999,609.6 0.9429796438999999,52.16792906549999,609.6 0.9368956062,52.1670483157,609.6 0.9309699841,52.1658258326,609.6 0.9252534515999999,52.1642720733,609.6 0.91979488,52.1624003276,609.6 0.9146409181999999,52.1602266031,609.6 0.9098355913,52.15776948760001,609.6 0.9054199238000001,52.155049989,609.6 0.9014315882,52.1520913543,609.6 0.8979045841,52.1489188703,609.6 0.8948689485,52.1455596457,609.6 0.8923505021,52.1420423786,609.6 0.8903706309,52.13839711069999,609.6 0.8889461078999999,52.1346549692,609.6 0.8880889534999999,52.130847901,609.6 0.887806338,52.1270083989,609.6 0.8881005247,52.1231692242,609.6 0.8889688560999999,52.1193631272,609.6 0.8904037816000001,52.1156225676,609.6 0.8923929263000001,52.1119794383,609.6 0.8949192016,52.1084647939,609.6 0.8979609547000001,52.1051085866,609.6 0.9014921567,52.1019394118,609.6 0.9054826276,52.0989842656,609.6 0.9098982951,52.0962683158,609.6 0.9147014867,52.09381468880001,609.6 0.9198512507,52.0916442735,609.6 0.9253037047,52.0897755451,609.6 0.9310124084,52.0882244085,609.6 0.9369287568999999,52.087004064,609.6 0.9430023922,52.0861248961,609.6 0.9491816283999999,52.0855943853,609.6 0.9554138889,52.0854170454,609.6 0.9616461494,52.0855943853,609.6 0.9678253855999999,52.0861248961,609.6 0.9738990208,52.087004064,609.6 0.9798153694,52.0882244085,609.6 0.9855240730999999,52.0897755451,609.6 0.9909765270999999,52.0916442735,609.6 0.9961262910000002,52.09381468880001,609.6 1.0009294826,52.0962683158,609.6 1.0053451502,52.0989842656,609.6 1.0093356211,52.1019394118,609.6 1.0128668231,52.1051085866,609.6 1.0159085762,52.1084647939,609.6 1.0184348515,52.1119794383,609.6 1.0204239962,52.1156225676,609.6 1.0218589216,52.1193631272,609.6 1.0227272531,52.1231692242,609.6 1.0230214398,52.1270083989,609.6 1.0227388243,52.130847901,609.6 1.0218816699,52.1346549692,609.6 1.0204571469,52.13839711069999,609.6 1.0184772757,52.1420423786,609.6 1.0159588292,52.1455596457,609.6 1.0129231937,52.1489188703,609.6 1.0093961896,52.1520913543,609.6 1.005407854,52.155049989,609.6 1.0009921865,52.15776948760001,609.6 0.9961868596,52.1602266031,609.6 0.9910328978,52.1624003276,609.6 0.9855743262,52.1642720733,609.6 0.9798577937,52.1658258326,609.6 0.9739321716,52.1670483157,609.6 0.9678481339,52.16792906549999,609.6 0.9616577205,52.16846054749999,609.6 0.9554138889,52.1686382148,609.6 + + + + +
+ + EGRU230B WATTISHAM RWY 05 + 520513N 0005340E -
520537N 0005305E -
520609N 0005402E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520545N 0005438E -
520513N 0005340E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8945785833,52.08708213889999,609.6 0.9104756667,52.09594825,609.6 0.9069544023,52.0980224587,609.6 0.9036846797,52.10024747229999,609.6 0.9006835277999999,52.10261175,609.6 0.8847938611,52.0937486944,609.6 0.8945785833,52.08708213889999,609.6 + + + + +
+ + EGRU230C WATTISHAM RWY 23 + 521004N 0010104E -
520940N 0010139E -
520905N 0010037E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520929N 0010001E -
521004N 0010104E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0178328056,52.16778141670001,609.6 1.0003954167,52.1581005278,609.6 1.0039183892,52.1560243877,609.6 1.0071885817,52.15379737890001,609.6 1.010189,52.1514311111,609.6 1.0276337778,52.1611149444,609.6 1.0178328056,52.16778141670001,609.6 + + + + +
+ + EGRU231A OLD BUCKENHAM + A circle, 2 NM radius, centred at 522951N 0010307E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0520222222,52.5308612731,609.6 1.0464101911,52.5306847192,609.6 1.0408577828,52.5301569332,609.6 1.0354239821,52.5292835223,609.6 1.0301665059,52.5280737648,609.6 1.0251411855,52.5265405113,609.6 1.0204013713,52.5247000473,609.6 1.0159973633,52.5225719192,609.6 1.0119758757,52.5201787251,609.6 1.0083795406,52.51754587420001,609.6 1.0052464557,52.5147013154,609.6 1.0026097816,52.5116752395,609.6 1.0004973925,52.5084997572,609.6 0.9989315839,52.5052085578,609.6 0.9979288401999999,52.5018365507,609.6 0.9974996651,52.4984194941,609.6 0.9976484752999999,52.494993616,609.6 0.9983735593,52.49159522939999,609.6 0.9996671014000001,52.4882603475,609.6 1.00151527,52.4850243027,609.6 1.0038983689,52.48192137259999,609.6 1.0067910512,52.47898441779999,609.6 1.0101625908,52.47624453499999,609.6 1.0139772115,52.47373072850001,609.6 1.0181944671,52.4714696049,609.6 1.0227696711,52.4694850923,609.6 1.0276543694,52.4677981888,609.6 1.032796852,52.46642674120001,609.6 1.0381426984,52.4653852575,609.6 1.0436353506,52.4646847541,609.6 1.0492167076,52.4643326403,609.6 1.0548277368,52.4643326403,609.6 1.0604090939,52.4646847541,609.6 1.065901746,52.4653852575,609.6 1.0712475924,52.46642674120001,609.6 1.0763900751,52.4677981888,609.6 1.0812747734,52.4694850923,609.6 1.0858499774,52.4714696049,609.6 1.090067233,52.47373072850001,609.6 1.0938818536,52.47624453499999,609.6 1.0972533933,52.47898441779999,609.6 1.1001460755,52.48192137259999,609.6 1.1025291745,52.4850243027,609.6 1.104377343,52.4882603475,609.6 1.1056708852,52.49159522939999,609.6 1.1063959692,52.494993616,609.6 1.1065447793,52.4984194941,609.6 1.1061156042,52.5018365507,609.6 1.1051128606,52.5052085578,609.6 1.1035470519,52.5084997572,609.6 1.1014346628,52.5116752395,609.6 1.0987979888,52.5147013154,609.6 1.0956649038,52.51754587420001,609.6 1.0920685687,52.5201787251,609.6 1.0880470812,52.5225719192,609.6 1.0836430731,52.5247000473,609.6 1.0789032589,52.5265405113,609.6 1.0738779385,52.5280737648,609.6 1.0686204623,52.5292835223,609.6 1.0631866617,52.5301569332,609.6 1.0576342533,52.5306847192,609.6 1.0520222222,52.5308612731,609.6 + + + + +
+ + EGRU231B OLD BUCKENHAM RWY 02 + 522715N 0010159E -
522726N 0010110E -
522806N 0010133E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522755N 0010223E -
522715N 0010159E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0331583333,52.4542777778,609.6 1.0395878889,52.4651658333,609.6 1.0348536529,52.4659820364,609.6 1.0302589954,52.4670554677,609.6 1.0258412778,52.4683773889,609.6 1.0193194444,52.4573277778,609.6 1.0331583333,52.4542777778,609.6 + + + + +
+ + EGRU231C OLD BUCKENHAM RWY 20 + 523242N 0010416E -
523231N 0010506E -
523138N 0010435E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523149N 0010345E -
523242N 0010416E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0711527778,52.5449833333,609.6 1.0624254444,52.5302505833,609.6 1.0672134848,52.5295449608,609.6 1.0718775255,52.52857877249999,609.6 1.0763795,52.5273598889,609.6 1.0850166667,52.5419333333,609.6 1.0711527778,52.5449833333,609.6 + + + + +
+ + EGRU231D OLD BUCKENHAM RWY 07 + 522822N 0005900E -
522851N 0005837E -
522915N 0010000E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522846N 0010023E -
522822N 0005900E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9833472222,52.47273333329999,609.6 1.0063476944,52.4793926667,609.6 1.003847467,52.4819797884,609.6 1.0017391739,52.4846939569,609.6 1.0000400278,52.4875130833,609.6 0.9770555556000001,52.4808583333,609.6 0.9833472222,52.47273333329999,609.6 + + + + +
+ + EGRU231E OLD BUCKENHAM RWY 25 + 523120N 0010715E -
523051N 0010737E -
523027N 0010615E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523057N 0010552E -
523120N 0010715E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1207472222,52.5223555556,609.6 1.0977450556,52.51572966669999,609.6 1.1002399859,52.5131402516,609.6 1.1023418593,52.5104241196,609.6 1.1040336389,52.50760341669999,609.6 1.12705,52.5142333333,609.6 1.1207472222,52.5223555556,609.6 + + + + +
+ + EGRU231F OLD BUCKENHAM RWY 07L + 522828N 0005916E -
522857N 0005853E -
522917N 0005959E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
522847N 0010021E -
522828N 0005916E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9878055556000001,52.4744638889,609.6 1.0059615,52.4797591944,609.6 1.0035164819,52.4823666245,609.6 1.0014662454,52.485097998,609.6 0.9998275556,52.4879310833,609.6 0.9814722222,52.4825777778,609.6 0.9878055556000001,52.4744638889,609.6 + + + + +
+ + EGRU231G OLD BUCKENHAM RWY 25R + 523122N 0010711E -
523053N 0010734E -
523030N 0010613E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522951N 0010307E to
523059N 0010550E -
523122N 0010711E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1198027778,52.5228194444,609.6 1.0971755833,52.51625308330001,609.6 1.0997504044,52.5136926291,609.6 1.1019361107,52.51100094609999,609.6 1.1037149444,52.5081999722,609.6 1.1261416667,52.5147083333,609.6 1.1198027778,52.5228194444,609.6 + + + + +
+ + EGRU232A NORWICH + A circle, 2.5 NM radius, centred at 524033N 0011658E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.2826638889,52.7175398849,609.6 1.2763419716,52.7173622309,609.6 1.2700741436,52.7168307887,609.6 1.2639140275,52.7159501052,609.6 1.2579143166,52.71472771460001,609.6 1.252126321,52.713174074,609.6 1.2465995249,52.7113024726,609.6 1.2413811617,52.7091289177,609.6 1.236515808,52.7066719965,609.6 1.232045001,52.703952716,609.6 1.2280068838,52.7009943225,609.6 1.2244358797,52.6978221014,609.6 1.2213623995,52.6944631601,609.6 1.218812584,52.6909461951,609.6 1.2168080836,52.687301246,609.6 1.2153658776,52.6835594382,609.6 1.2144981329,52.6797527158,609.6 1.2142121053,52.675913569,609.6 1.2145100826,52.6720747562,609.6 1.2153893702,52.6682690245,609.6 1.216842319,52.6645288303,609.6 1.2188563964,52.66088606289999,609.6 1.2214142969,52.6573717732,609.6 1.2244940948,52.6540159098,609.6 1.2280694342,52.6508470644,609.6 1.2321097566,52.6478922294,609.6 1.2365805636,52.64517656900001,609.6 1.2414437122,52.6427232063,609.6 1.2466577401,52.6405530271,609.6 1.2521782185,52.6386845036,609.6 1.2579581291,52.6371335382,609.6 1.263948263,52.6359133293,609.6 1.2700976362,52.63503425940001,609.6 1.2763539214,52.634503808,609.6 1.2826638889,52.6343264879,609.6 1.2889738564,52.634503808,609.6 1.2952301415,52.63503425940001,609.6 1.3013795148,52.6359133293,609.6 1.3073696486,52.6371335382,609.6 1.3131495593,52.6386845036,609.6 1.3186700377,52.6405530271,609.6 1.3238840656,52.6427232063,609.6 1.3287472142,52.64517656900001,609.6 1.3332180212,52.6478922294,609.6 1.3372583436,52.6508470644,609.6 1.3408336829,52.6540159098,609.6 1.3439134809,52.6573717732,609.6 1.3464713814,52.66088606289999,609.6 1.3484854587,52.6645288303,609.6 1.3499384076,52.6682690245,609.6 1.3508176951,52.6720747562,609.6 1.3511156725,52.675913569,609.6 1.3508296449,52.6797527158,609.6 1.3499619002,52.6835594382,609.6 1.3485196942,52.687301246,609.6 1.3465151938,52.6909461951,609.6 1.3439653783,52.6944631601,609.6 1.3408918981,52.6978221014,609.6 1.337320894,52.7009943225,609.6 1.3332827768,52.703952716,609.6 1.3288119698,52.7066719965,609.6 1.323946616,52.7091289177,609.6 1.3187282529,52.7113024726,609.6 1.3132014568,52.713174074,609.6 1.3074134611,52.71472771460001,609.6 1.3014137503,52.7159501052,609.6 1.2952536342,52.7168307887,609.6 1.2889858062,52.7173622309,609.6 1.2826638889,52.7175398849,609.6 + + + + +
+ + EGRU232B NORWICH RWY 09 + 524015N 0011143E -
524047N 0011142E -
524048N 0011252E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to
524015N 0011253E -
524015N 0011143E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.1952277778,52.67074722220001,609.6 1.2147172778,52.6709072222,609.6 1.2142956962,52.6738970556,609.6 1.2142297104,52.67689758249999,609.6 1.2145197222,52.6798931944,609.6 1.1950472222,52.6797333333,609.6 1.1952277778,52.67074722220001,609.6 + + + + +
+ + EGRU232C NORWICH RWY 27 + 524052N 0012212E -
524019N 0012213E -
524019N 0012103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 524033N 0011658E to
524051N 0012102E -
524052N 0012212E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3700972222,52.6810555556,609.6 1.3506258889,52.68092125,609.6 1.3510383033,52.6779309394,609.6 1.3510950081,52.6749303384,609.6 1.3507957778,52.6719350556,609.6 1.3702833333,52.6720694444,609.6 1.3700972222,52.6810555556,609.6 + + + + +
+ + EGRU233A CHETWYND + A circle, 2 NM radius, centred at 524842N 0022425W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4070333333,52.8448400548,609.6 -2.4126857617,52.84466350879999,609.6 -2.4182781367,52.8441357465,609.6 -2.4237510472,52.8432623748,609.6 -2.4290463597,52.84205267199999,609.6 -2.4341078399,52.8405194884,609.6 -2.4388817526,52.8386791092,609.6 -2.4433174353,52.83655108,609.6 -2.4473678374,52.83415799869999,609.6 -2.4509900203,52.8315252736,609.6 -2.4541456127,52.82868085280001,609.6 -2.4568012165,52.82565492580001,609.6 -2.4589287581,52.8224796025,609.6 -2.4605057833,52.8191885707,609.6 -2.4615156908,52.815816738,609.6 -2.4619479035,52.8123998614,609.6 -2.4617979748,52.8089741667,609.6 -2.4610676306,52.80557596489999,609.6 -2.4597647448,52.8022412674,609.6 -2.4579032504,52.7990054042,609.6 -2.4555029865,52.79590265089999,609.6 -2.452589484,52.7929658657,609.6 -2.4491936904,52.7902261431,609.6 -2.4453516401,52.78771248529999,609.6 -2.4411040699,52.7854514968,609.6 -2.4364959876,52.78346710400001,609.6 -2.4315761948,52.781780303,609.6 -2.4263967722,52.7804089394,609.6 -2.4210125304,52.7793675197,609.6 -2.4154804323,52.7786670595,609.6 -2.4098589945,52.77831496749999,609.6 -2.4042076722,52.77831496749999,609.6 -2.3985862344,52.7786670595,609.6 -2.3930541363,52.7793675197,609.6 -2.3876698944,52.7804089394,609.6 -2.3824904719,52.781780303,609.6 -2.3775706791,52.78346710400001,609.6 -2.3729625967,52.7854514968,609.6 -2.3687150266,52.78771248529999,609.6 -2.3648729763,52.7902261431,609.6 -2.3614771827,52.7929658657,609.6 -2.3585636801,52.79590265089999,609.6 -2.3561634163,52.7990054042,609.6 -2.3543019219,52.8022412674,609.6 -2.3529990361,52.80557596489999,609.6 -2.3522686919,52.8089741667,609.6 -2.3521187632,52.8123998614,609.6 -2.3525509758,52.815816738,609.6 -2.3535608834,52.8191885707,609.6 -2.3551379086,52.8224796025,609.6 -2.3572654502,52.82565492580001,609.6 -2.359921054,52.82868085280001,609.6 -2.3630766464,52.8315252736,609.6 -2.3666988293,52.83415799869999,609.6 -2.3707492314,52.83655108,609.6 -2.3751849141,52.8386791092,609.6 -2.3799588268,52.8405194884,609.6 -2.385020307,52.84205267199999,609.6 -2.3903156195,52.8432623748,609.6 -2.39578853,52.8441357465,609.6 -2.4013809049,52.84466350879999,609.6 -2.4070333333,52.8448400548,609.6 + + + + +
+ + EGRU234A HONINGTON + A circle, 2 NM radius, centred at 522036N 0004648E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7799999999999999,52.3766204797,609.6 0.7744075413000001,52.376443922,609.6 0.7688744967000001,52.3759161243,609.6 0.7634596447000001,52.375042694,609.6 0.7582205001000001,52.3738329095,609.6 0.7532126991,52.3722996215,609.6 0.7484894056000001,52.3704591158,609.6 0.7441007439000001,52.3683309388,609.6 0.7400932654999999,52.36593768910001,609.6 0.7365094537,52.3633047762,609.6 0.7333872738,52.3604601494,609.6 0.7307597713000001,52.35743399999999,609.6 0.7286547238,52.3542584394,609.6 0.7270943498,52.35096715749999,609.6 0.7260950772,52.3475950644,609.6 0.7256673738999999,52.3441779193,609.6 0.7258156422999998,52.3407519509,609.6 0.726538178,52.3373534732,609.6 0.7278271932,52.33401850060001,609.6 0.7296689055000001,52.3307823664,609.6 0.7320436881,52.3276793494,609.6 0.7349262829999998,52.3247423112,609.6 0.7382860716,52.3220023496,609.6 0.7420874025,52.31948847,609.6 0.7462899707000001,52.3172272799,609.6 0.7508492450000001,52.3152427085,609.6 0.7557169398999999,52.31355575460001,609.6 0.7608415249,52.3121842658,609.6 0.7661687685,52.3111427505,609.6 0.7716423088,52.3104422259,609.6 0.7772042465,52.3100901013,609.6 0.7827957535,52.3100901013,609.6 0.7883576912,52.3104422259,609.6 0.7938312315,52.3111427505,609.6 0.7991584750999999,52.3121842658,609.6 0.8042830600999999,52.31355575460001,609.6 0.809150755,52.3152427085,609.6 0.8137100293,52.3172272799,609.6 0.8179125975,52.31948847,609.6 0.8217139284,52.3220023496,609.6 0.825073717,52.3247423112,609.6 0.8279563119,52.3276793494,609.6 0.8303310945000001,52.3307823664,609.6 0.8321728068000002,52.33401850060001,609.6 0.833461822,52.3373534732,609.6 0.8341843577,52.3407519509,609.6 0.8343326261,52.3441779193,609.6 0.8339049227999999,52.3475950644,609.6 0.8329056502,52.35096715749999,609.6 0.8313452762,52.3542584394,609.6 0.8292402287,52.35743399999999,609.6 0.8266127262,52.3604601494,609.6 0.8234905463,52.3633047762,609.6 0.8199067345,52.36593768910001,609.6 0.8158992561,52.3683309388,609.6 0.8115105944000001,52.3704591158,609.6 0.8067873008999998,52.3722996215,609.6 0.8017794999000001,52.3738329095,609.6 0.7965403553,52.375042694,609.6 0.7911255033000001,52.3759161243,609.6 0.7855924587000001,52.376443922,609.6 0.7799999999999999,52.3766204797,609.6 + + + + +
+ + EGRU234B HONINGTON + 521947N 0004055E -
522019N 0004047E -
522035N 0004332E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to
522003N 0004340E -
521947N 0004055E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6818130278,52.3296939722,609.6 0.7278162222,52.33404155560001,609.6 0.7266595214,52.3369605969,609.6 0.7259369978,52.33993162220001,609.6 0.7256546111,52.3429304444,609.6 0.6795900833,52.3385770556,609.6 0.6818130278,52.3296939722,609.6 + + + + +
+ + EGRU234C HONINGTON + 522121N 0005151E -
522049N 0005159E -
522039N 0005004E thence anti-clockwise by the arc of a circle radius 2 NM centred on 522036N 0004648E to
522110N 0004955E -
522121N 0005151E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8642396389,52.3559142222,609.6 0.8320553889,52.3529141111,609.6 0.8332521005999999,52.3500010766,609.6 0.8340149860999999,52.3470338347,609.6 0.8343379166999999,52.3440365556,609.6 0.8664634722,52.3470311667,609.6 0.8642396389,52.3559142222,609.6 + + + + +
+ + EGRU235 HMP BEDFORD + 520840N 0002812W -
520836N 0002756W -
520822N 0002743W -
520804N 0002758W -
520807N 0002824W -
520815N 0002840W -
520835N 0002832W -
520840N 0002812W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 115 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4699694444,52.14451944439999,182.88 -0.4754777778,52.14314722220001,182.88 -0.4778222222,52.1376055556,182.88 -0.473425,52.1351944444,182.88 -0.4660722222,52.1345444444,182.88 -0.4620055556,52.1395611111,182.88 -0.4655805556,52.1431944444,182.88 -0.4699694444,52.14451944439999,182.88 + + + + +
+ + EGRU236 HMP BIRMINGHAM + 522954N 0015626W -
522952N 0015553W -
522944N 0015547W -
522925N 0015547W -
522918N 0015558W -
522917N 0015633W -
522944N 0015648W -
522954N 0015626W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 483 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9406583333,52.4983111111,274.32 -1.9467111111,52.49555277780001,274.32 -1.9424222222,52.4879805556,274.32 -1.9326861111,52.48821944440001,274.32 -1.9296444444,52.4903972222,274.32 -1.9297361111,52.49549166669999,274.32 -1.9314527778,52.4976833333,274.32 -1.9406583333,52.4983111111,274.32 + + + + +
+ + EGRU237 HMP BURE + 524549N 0012029E -
524552N 0012052E -
524537N 0012123E -
524511N 0012049E -
524532N 0012007E -
524549N 0012029E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 77 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3413777778,52.763725,152.4 1.3352138889,52.7589055556,152.4 1.3470583333,52.7531694444,152.4 1.3564444444,52.7601555556,152.4 1.3476527778,52.7643277778,152.4 1.3413777778,52.763725,152.4 + + + + +
+ + EGRU238 HMP DOVEGATE + 525234N 0014708W -
525234N 0014639W -
525215N 0014608W -
525150N 0014649W -
525212N 0014724W -
525226N 0014723W -
525234N 0014708W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 243 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7855305556,52.876175,213.36 -1.7896972222,52.8737777778,213.36 -1.7901194444,52.869925,213.36 -1.7803777778,52.8639833333,213.36 -1.7689,52.87088333330001,213.36 -1.7776138889,52.8761416667,213.36 -1.7855305556,52.876175,213.36 + + + + +
+ + EGRU239 HMP DRAKE HALL + 525309N 0021429W -
525249N 0021352W -
525224N 0021421W -
525223N 0021445W -
525241N 0021503W -
525255N 0021453W -
525309N 0021429W
Upper limit: 800 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 347 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2413305556,52.8857111111,243.84 -2.2480138889,52.8818361111,243.84 -2.2509111111,52.87817500000001,243.84 -2.2458916667,52.8730916667,243.84 -2.2392972222,52.8733055556,243.84 -2.23105,52.88023888890001,243.84 -2.2413305556,52.8857111111,243.84 + + + + +
+ + EGRU240 HMP FEATHERSTONE/BRINSFORD/OAKWOOD + 523917N 0020718W -
523923N 0020623W -
523849N 0020555W -
523821N 0020609W -
523826N 0020658W -
523841N 0020716W -
523917N 0020718W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 393 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1215583333,52.6548,243.84 -2.1211027778,52.6446611111,243.84 -2.1161916667,52.64061388889999,243.84 -2.1026027778,52.63921388890001,243.84 -2.0985861111,52.6469722222,243.84 -2.1064611111,52.6564722222,243.84 -2.1215583333,52.6548,243.84 + + + + +
+ + EGRU241 HMP FIVE WELLS + 521728N 0004128W -
521727N 0004101W -
521710N 0004054W -
521646N 0004102W -
521645N 0004141W -
521658N 0004205W -
521714N 0004205W -
521728N 0004128W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 226 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6910527778,52.290975,213.36 -0.7013305556,52.2872861111,213.36 -0.7012527777999999,52.2828583333,213.36 -0.6947,52.2791583333,213.36 -0.6839666666999999,52.279475,213.36 -0.6817027778,52.2861777778,213.36 -0.6836805556,52.2908,213.36 -0.6910527778,52.290975,213.36 + + + + +
+ + EGRU242 HMP FOSSE WAY + 523531N 0010859W -
523528N 0010812W -
523443N 0010815W -
523439N 0010853W -
523446N 0010924W -
523531N 0010859W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 298 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1498138889,52.59188888890001,213.36 -1.1565666667,52.5795416667,213.36 -1.1481777778,52.5774944444,213.36 -1.1375694444,52.5785861111,213.36 -1.136575,52.5911527778,213.36 -1.1498138889,52.59188888890001,213.36 + + + + +
+ + EGRU243 HMP FOSTON HALL + 525313N 0014400W -
525314N 0014325W -
525303N 0014256W -
525237N 0014314W -
525237N 0014357W -
525313N 0014400W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 223 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.733425,52.8869805556,213.36 -1.732525,52.8769722222,213.36 -1.7205361111,52.8770083333,213.36 -1.715675,52.8840833333,213.36 -1.7236166667,52.8872555556,213.36 -1.733425,52.8869805556,213.36 + + + + +
+ + EGRU244 HMP GARTREE + 523004N 0005752W -
522959N 0005714W -
522931N 0005708W -
522921N 0005801W -
522945N 0005814W -
523004N 0005752W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 398 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.964475,52.5010833333,243.84 -0.9705583333,52.4957944444,243.84 -0.9670111111,52.4890361111,243.84 -0.9521666667000001,52.49195,243.84 -0.9539333333000001,52.4998388889,243.84 -0.964475,52.5010833333,243.84 + + + + +
+ + EGRU245 HMP HEWELL + 521951N 0015926W -
521935N 0015833W -
521911N 0015853W -
521911N 0015919W -
521917N 0015936W -
521930N 0015948W -
521951N 0015926W
Upper limit: 900 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 443 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9904305556,52.33096666670001,274.32 -1.9966583333,52.32496388890001,274.32 -1.9934444444,52.3214833333,274.32 -1.9885444444,52.3197611111,274.32 -1.9815083333,52.3198361111,274.32 -1.9757583333,52.3262611111,274.32 -1.9904305556,52.33096666670001,274.32 + + + + +
+ + EGRU246 HMP HIGHPOINT + 520847N 0003034E -
520845N 0003109E -
520801N 0003134E -
520749N 0003019E -
520822N 0003003E -
520847N 0003034E
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 390 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5095194444,52.1464944444,243.84 0.5008166667,52.1393277778,243.84 0.5051555556,52.1304,243.84 0.5260694444,52.1337222222,243.84 0.5192861111,52.1459222222,243.84 0.5095194444,52.1464944444,243.84 + + + + +
+ + EGRU247 HMP LEICESTER + 523755N 0010756W -
523744N 0010724W -
523728N 0010735W -
523721N 0010753W -
523730N 0010818W -
523749N 0010821W -
523755N 0010756W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 215 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1321138889,52.6320527778,213.36 -1.1391555556,52.63035,213.36 -1.1383638889,52.6250333333,213.36 -1.1312555556,52.62247777779999,213.36 -1.126375,52.6244472222,213.36 -1.1232083333,52.6289055556,213.36 -1.1321138889,52.6320527778,213.36 + + + + +
+ + EGRU248 HMP LITTLEHEY + 521707N 0001916W -
521706N 0001824W -
521656N 0001811W -
521637N 0001817W -
521627N 0001846W -
521633N 0001920W -
521648N 0001924W -
521707N 0001916W
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 173 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3211638889,52.2851944444,182.88 -0.3232416667,52.2799638889,182.88 -0.3221722222,52.2757138889,182.88 -0.31275,52.2740583333,182.88 -0.3047,52.2770305556,182.88 -0.3030472222,52.28208888889999,182.88 -0.3065888889,52.2849,182.88 -0.3211638889,52.2851944444,182.88 + + + + +
+ + EGRU249 HMP LONG LARTIN + 520649N 0015133W -
520643N 0015034W -
520609N 0015055W -
520616N 0015158W -
520649N 0015133W
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 160 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8592277778,52.1137055556,182.88 -1.8661638889,52.1045055556,182.88 -1.8485638889,52.10248055560001,182.88 -1.8427472222,52.1118416667,182.88 -1.8592277778,52.1137055556,182.88 + + + + +
+ + EGRU250 HMP NORWICH + 523836N 0011852E -
523838N 0011915E -
523811N 0011938E -
523801N 0011938E -
523748N 0011855E -
523753N 0011845E -
523821N 0011823E -
523836N 0011852E
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Norwich Airport (FRZ - EGRU232A) and HMPPS.
Contact online:
https://www.norwichairport.co.uk/airfield-pilot-information/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 160 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.3143916667,52.643425,182.88 1.306325,52.63922777780001,182.88 1.3124305556,52.6312888889,182.88 1.315325,52.62987222219999,182.88 1.3273166667,52.6334861111,182.88 1.3273055556,52.6363027778,182.88 1.3208805556,52.6439222222,182.88 1.3143916667,52.643425,182.88 + + + + +
+ + EGRU251 HMP NOTTINGHAM + 525921N 0010935W -
525925N 0010857W -
525856N 0010848W -
525850N 0010906W -
525848N 0010942W -
525905N 0010948W -
525915N 0010946W -
525921N 0010935W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 255 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1597333333,52.9892694444,213.36 -1.1628611111,52.9873611111,213.36 -1.1632805556,52.9847805556,213.36 -1.1615972222,52.9799111111,213.36 -1.1516527778,52.98049166669999,213.36 -1.1467583333,52.9822333333,213.36 -1.1490861111,52.99026666669999,213.36 -1.1597333333,52.9892694444,213.36 + + + + +
+ + EGRU252 HMP PETERBOROUGH + 523529N 0001553W -
523535N 0001524W -
523459N 0001501W -
523451N 0001534W -
523458N 0001559W -
523506N 0001602W -
523520N 0001602W -
523529N 0001553W
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 62 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2647388889,52.5912555556,152.4 -0.2671416667,52.58887777779999,152.4 -0.2673222222,52.5848972222,152.4 -0.2662805556,52.58265277779999,152.4 -0.259575,52.58096666670001,152.4 -0.2503805556,52.5831861111,152.4 -0.2566833333,52.59310277779999,152.4 -0.2647388889,52.5912555556,152.4 + + + + +
+ + EGRU253 HMP RYE HILL/OLNEY + 522004N 0011457W -
522005N 0011435W -
521956N 0011413W -
521948N 0011408W -
521937N 0011406W -
521925N 0011421W -
521919N 0011455W -
521920N 0011535W -
522000N 0011513W -
522004N 0011457W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 361 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2492583333,52.3345611111,243.84 -1.2535833333,52.3334,243.84 -1.2598194444,52.3222833333,243.84 -1.24855,52.3219944444,243.84 -1.2393027778,52.32349166669999,243.84 -1.2349888889,52.3268305556,243.84 -1.2354277778,52.3299555556,243.84 -1.2369777778,52.3322388889,243.84 -1.2430083333,52.3347111111,243.84 -1.2492583333,52.3345611111,243.84 + + + + +
+ + EGRU254 HMP STAFFORD + 524854N 0020734W -
524902N 0020643W -
524841N 0020635W -
524828N 0020639W -
524820N 0020720W -
524854N 0020734W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 267 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1262083333,52.8149555556,213.36 -2.1221472222,52.8056,213.36 -2.1107027778,52.8076833333,213.36 -2.1095888889,52.81147500000001,213.36 -2.1118638889,52.8170972222,213.36 -2.1262083333,52.8149555556,213.36 + + + + +
+ + EGRU255 HMP STOCKEN + 524512N 0003449W -
524513N 0003414W -
524450N 0003403W -
524434N 0003430W -
524429N 0003454W -
524440N 0003514W -
524449N 0003518W -
524504N 0003516W -
524512N 0003449W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 371 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5802055556,52.75343611110001,243.84 -0.5877777778,52.75105,243.84 -0.5882805556,52.7468638889,243.84 -0.5872194444,52.74452777780001,243.84 -0.5816472222,52.7414027778,243.84 -0.5750555556,52.74279166670001,243.84 -0.5675138889,52.74725,243.84 -0.5705249999999999,52.7535111111,243.84 -0.5802055556,52.75343611110001,243.84 + + + + +
+ + EGRU256 HMP STOKE HEATH + 525231N 0023138W -
525224N 0023119W -
525231N 0023107W -
525216N 0023045W -
525202N 0023043W -
525157N 0023052W -
525142N 0023059W -
525152N 0023157W -
525231N 0023138W
Upper limit: 700 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by RAF Shawbury (Ternhill FRZ - EGRU206A) and HMPPS.
Contact: RAF Shawbury Station Ops 01939-250341 ext 7163 shy-ops@mod.gov.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 269 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5272138889,52.87520555559999,213.36 -2.5324694444,52.86448888890001,213.36 -2.5165222222,52.8617055556,213.36 -2.5145416667,52.865825,213.36 -2.5119222222,52.8672861111,213.36 -2.5124138889,52.87117499999999,213.36 -2.5187416667,52.87525555560001,213.36 -2.5219416667,52.87341388889999,213.36 -2.5272138889,52.87520555559999,213.36 + + + + +
+ + EGRU257 HMP SWINFEN HALL + 523936N 0014816W -
523921N 0014741W -
523908N 0014741W -
523849N 0014810W -
523857N 0014834W -
523910N 0014858W -
523936N 0014816W
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 309 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.8045694444,52.6599611111,243.84 -1.8159944444,52.6529083333,243.84 -1.8095166667,52.6490972222,243.84 -1.8028055556,52.6468833333,243.84 -1.794625,52.6522055556,243.84 -1.7946388889,52.65585277779999,243.84 -1.8045694444,52.6599611111,243.84 + + + + +
+ + EGRU258 HMP WARREN HILL + 520356N 0012736E -
520335N 0012812E -
520319N 0012809E -
520307N 0012727E -
520333N 0012659E -
520356N 0012736E
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 59 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.4600444444,52.06553888890001,152.4 1.449675,52.0590805556,152.4 1.4574888889,52.0519277778,152.4 1.4692555556,52.0552388889,152.4 1.4700805556,52.05961666670001,152.4 1.4600444444,52.06553888890001,152.4 + + + + +
+ + EGRU259 HMP WAYLAND + 523337N 0005103E -
523337N 0005158E -
523256N 0005158E -
523256N 0005109E -
523313N 0005056E -
523337N 0005103E
Upper limit: 600 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 189 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8507277778,52.5603666667,182.88 0.8488444444,52.5535222222,182.88 0.8524499999999999,52.54898333330001,182.88 0.8659805556,52.5489666667,182.88 0.86615,52.5603555556,182.88 0.8507277778,52.5603666667,182.88 + + + + +
+ + EGRU260 HMP WHATTON + 525709N 0005519W -
525708N 0005442W -
525710N 0005428W -
525659N 0005406W -
525634N 0005402W -
525638N 0005523W -
525709N 0005519W
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 87 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9219444444,52.9525027778,152.4 -0.9229722222,52.94383333330001,152.4 -0.900525,52.9426555556,152.4 -0.9015999999999998,52.94975,152.4 -0.9076666667,52.95289166669999,152.4 -0.9117305556,52.95223055560001,152.4 -0.9219444444,52.9525027778,152.4 + + + + +
+ + EGRU261 HMP WHITEMOOR + 523445N 0000411E -
523456N 0000509E -
523421N 0000527E -
523410N 0000430E -
523445N 0000411E
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 17 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0698444444,52.5791083333,152.4 0.0748722222,52.5693833333,152.4 0.0908222222,52.5725166667,152.4 0.08574444439999999,52.58228333329999,152.4 0.0698444444,52.5791083333,152.4 + + + + +
+ + EGRU262 HMP WOODHILL + 520113N 0004826W -
520038N 0004752W -
520021N 0004838W -
520056N 0004913W -
520113N 0004826W
Upper limit: 900 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 401 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.807125,52.0203222222,274.32 -0.8203583333000001,52.01555555560001,274.32 -0.8106138888999999,52.0057194444,274.32 -0.7978666666999999,52.01063333329999,274.32 -0.807125,52.0203222222,274.32 + + + + +
+ + EGRU301A VALLEY + A circle, 2.5 NM radius, centred at 531453N 0043207W
Upper limit: 2000 FT SFC
Lower limit: 0 FT SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5353333333,53.2897691896,609.6 -4.5417394023,53.2895915492,609.6 -4.5480906587,53.2890601481,609.6 -4.5543327631,53.2881795327,609.6 -4.5604123179,53.2869572374,609.6 -4.5662773276,53.2854037189,609.6 -4.5718776474,53.28353226620001,609.6 -4.5771654137,53.281358886,609.6 -4.5820954562,53.2789021651,609.6 -4.5866256844,53.27618310959999,609.6 -4.5907174486,53.273224965,609.6 -4.5943358686,53.2700530154,609.6 -4.597450131,53.2666943668,609.6 -4.6000337501,53.2631777142,609.6 -4.6020647903,53.25953309519999,609.6 -4.6035260505,53.2557916327,609.6 -4.6044052057,53.25198526850001,609.6 -4.604694908,53.2481464901,609.6 -4.6043928434,53.2443080527,609.6 -4.6035017468,53.2405027001,609.6 -4.6020293729,53.2367628853,609.6 -4.599988425,53.23312049379999,609.6 -4.5973964418,53.2296065728,609.6 -4.5942756435,53.22625106689999,609.6 -4.5906527385,53.2230825641,609.6 -4.5865586931,53.22012805289999,609.6 -4.5820284648,53.2174126938,609.6 -4.5771007037,53.2149596063,609.6 -4.5718174223,53.2127896729,609.6 -4.5662236383,53.2109213629,609.6 -4.5603669927,53.209370576,609.6 -4.5542973456,53.2081505083,609.6 -4.548066355,53.2072715406,609.6 -4.5417270399,53.2067411509,609.6 -4.5353333333,53.2065638516,609.6 -4.5289396267,53.2067411509,609.6 -4.5226003117,53.2072715406,609.6 -4.5163693211,53.2081505083,609.6 -4.510299674,53.209370576,609.6 -4.5044430283,53.2109213629,609.6 -4.4988492444,53.2127896729,609.6 -4.493565963,53.2149596063,609.6 -4.4886382018,53.2174126938,609.6 -4.4841079736,53.22012805289999,609.6 -4.4800139281,53.2230825641,609.6 -4.4763910232,53.22625106689999,609.6 -4.4732702249,53.2296065728,609.6 -4.4706782417,53.23312049379999,609.6 -4.4686372938,53.2367628853,609.6 -4.4671649199,53.2405027001,609.6 -4.4662738233,53.2443080527,609.6 -4.4659717587,53.2481464901,609.6 -4.4662614609,53.25198526850001,609.6 -4.4671406162,53.2557916327,609.6 -4.4686018763,53.25953309519999,609.6 -4.4706329166,53.2631777142,609.6 -4.4732165356,53.2666943668,609.6 -4.4763307981,53.2700530154,609.6 -4.4799492181,53.273224965,609.6 -4.4840409822,53.27618310959999,609.6 -4.4885712105,53.2789021651,609.6 -4.4935012529,53.281358886,609.6 -4.4987890193,53.28353226620001,609.6 -4.504389339,53.2854037189,609.6 -4.5102543488,53.2869572374,609.6 -4.5163339036,53.2881795327,609.6 -4.5225760079,53.2890601481,609.6 -4.5289272644,53.2895915492,609.6 -4.5353333333,53.2897691896,609.6 + + + + +
+ + EGRU301B VALLEY RWY 01 + 531154N 0043228W -
531158N 0043322W -
531229N 0043316W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531224N 0043223W -
531154N 0043228W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5412361111,53.1983583333,609.6 -4.5397092778,53.2066468056,609.6 -4.5446913844,53.2069446068,609.6 -4.5496247792,53.2074573908,609.6 -4.5544837778,53.2081825,609.6 -4.5561083333,53.1993472222,609.6 -4.5412361111,53.1983583333,609.6 + + + + +
+ + EGRU301C VALLEY RWY 19 + 531810N 0043213W -
531806N 0043120W -
531721N 0043128W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531723N 0043222W -
531810N 0043213W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5370638889,53.3026916667,609.6 -4.5394639444,53.2896954167,609.6 -4.5344489699,53.2897658191,609.6 -4.5294386237,53.2896188347,609.6 -4.5244591389,53.28925524999999,609.6 -4.5221555556,53.3017055556,609.6 -4.5370638889,53.3026916667,609.6 + + + + +
+ + EGRU301D VALLEY RWY 13 + 531646N 0043630W -
531711N 0043555W -
531642N 0043459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531618N 0043534W -
531646N 0043630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6082879167,53.2794899167,609.6 -4.5927136389,53.2715534167,609.6 -4.5897540887,53.2739730646,609.6 -4.5865109682,53.2762584688,609.6 -4.5830011389,53.2783977222,609.6 -4.5985659167,53.2863302778,609.6 -4.6082879167,53.2794899167,609.6 + + + + +
+ + EGRU301E VALLEY RWY 31 + 531253N 0042730W -
531228N 0042805W -
531305N 0042916W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531453N 0043207W to
531329N 0042841W -
531253N 0042730W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4584117778,53.2147212778,609.6 -4.4780087222,53.22475830560001,609.6 -4.4809704688,53.2223411037,609.6 -4.4842144577,53.2200582086,609.6 -4.4877238056,53.2179214722,609.6 -4.4681175556,53.2078808611,609.6 -4.4584117778,53.2147212778,609.6 + + + + +
+ + EGRU302A CAERNARFON + A circle, 2 NM radius, centred at 530607N 0042015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3376138889,53.1351023087,609.6 -4.3433043386,53.1349257699,609.6 -4.3489343296,53.1343980293,609.6 -4.3544440496,53.13352469369999,609.6 -4.3597749729,53.1323150412,609.6 -4.364870486,53.1307819219,609.6 -4.3696764915,53.1289416205,609.6 -4.3741419857,53.1268136824,609.6 -4.3782196013,53.1244207048,609.6 -4.3818661114,53.12178809540001,609.6 -4.3850428872,53.1189438015,609.6 -4.3877163068,53.1159180117,609.6 -4.3898581093,53.1127428348,609.6 -4.3914456909,53.1094519572,609.6 -4.3924623404,53.1060802854,609.6 -4.3928974115,53.1026635745,609.6 -4.3927464296,53.09923804879999,609.6 -4.3920111343,53.0958400175,609.6 -4.3906994541,53.09250549,609.6 -4.3888254173,53.0892697945,609.6 -4.3864089981,53.0861672042,609.6 -4.3834758997,53.0832305756,609.6 -4.3800572789,53.0804910008,609.6 -4.3761894124,53.0779774803,609.6 -4.3719133111,53.07571661670001,609.6 -4.3672742846,53.0737323344,609.6 -4.3623214621,53.0720456282,609.6 -4.357107273,53.070674342,609.6 -4.3516868947,53.0696329815,609.6 -4.3461176715,53.0689325613,609.6 -4.3404585112,53.0685804894,609.6 -4.3347692666,53.0685804894,609.6 -4.3291101063,53.0689325613,609.6 -4.3235408831,53.0696329815,609.6 -4.3181205048,53.070674342,609.6 -4.3129063157,53.0720456282,609.6 -4.3079534931,53.0737323344,609.6 -4.3033144667,53.07571661670001,609.6 -4.2990383653,53.0779774803,609.6 -4.2951704989,53.0804910008,609.6 -4.2917518781,53.0832305756,609.6 -4.2888187797,53.0861672042,609.6 -4.2864023605,53.0892697945,609.6 -4.2845283237,53.09250549,609.6 -4.2832166435,53.0958400175,609.6 -4.2824813481,53.09923804879999,609.6 -4.2823303663,53.1026635745,609.6 -4.2827654374,53.1060802854,609.6 -4.2837820869,53.1094519572,609.6 -4.2853696685,53.1127428348,609.6 -4.2875114709,53.1159180117,609.6 -4.2901848905,53.1189438015,609.6 -4.2933616663,53.12178809540001,609.6 -4.2970081764,53.1244207048,609.6 -4.3010857921,53.1268136824,609.6 -4.3055512863,53.1289416205,609.6 -4.3103572918,53.1307819219,609.6 -4.3154528048,53.1323150412,609.6 -4.3207837282,53.13352469369999,609.6 -4.3262934482,53.1343980293,609.6 -4.3319234391,53.1349257699,609.6 -4.3376138889,53.1351023087,609.6 + + + + +
+ + EGRU302B CAERNARFON RWY 07 + 530455N 0042437W -
530525N 0042455W -
530543N 0042331W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to
530512N 0042313W -
530455N 0042437W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4103138889,53.08182499999999,609.6 -4.3869033611,53.0867385278,609.6 -4.3889621559,53.0894737148,609.6 -4.3906033207,53.0923094586,609.6 -4.3918134167,53.09522269440001,609.6 -4.4152138889,53.09031111110001,609.6 -4.4103138889,53.08182499999999,609.6 + + + + +
+ + EGRU302C CAERNARFON RWY 25 + 530718N 0041554W -
530648N 0041536W -
530630N 0041700W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530607N 0042015W to
530701N 0041718W -
530718N 0041554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.2648611111,53.1217694444,609.6 -4.2882921389,53.1168824722,609.6 -4.286237965,53.114145571,609.6 -4.2846023923,53.1113083851,609.6 -4.2833986667,53.10839402780001,609.6 -4.2599555556,53.1132833333,609.6 -4.2648611111,53.1217694444,609.6 + + + + +
+ + EGRU303A WOODVALE + A circle, 2 NM radius, centred at 533454N 0030327W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0575277778,53.615002394,609.6 -3.0632825546,53.6148258671,609.6 -3.0689761866,53.6142981621,609.6 -3.0745481834,53.61342488569999,609.6 -3.0799393554,53.6122153156,609.6 -3.0850924473,53.6106823016,609.6 -3.0899527491,53.608842128,609.6 -3.0944686797,53.6067143394,609.6 -3.0985923365,53.60432153210001,609.6 -3.1022800041,53.6016891128,609.6 -3.1054926184,53.5988450274,609.6 -3.108196179,53.5958194632,609.6 -3.1103621078,53.5926445269,609.6 -3.1119675482,53.5893539031,609.6 -3.1129956032,53.5859824958,609.6 -3.1134355093,53.5825660578,609.6 -3.1132827447,53.57914081059999,609.6 -3.1125390718,53.5757430602,609.6 -3.1112125119,53.572408813,609.6 -3.109317254800001,53.5691733937,609.6 -3.1068735025,53.5660710724,609.6 -3.1039072508,53.5631347019,609.6 -3.1004500096,53.5603953712,609.6 -3.096538466300001,53.5578820774,609.6 -3.092214094900001,53.55562141970001,609.6 -3.087522716300001,53.55363732,609.6 -3.0825140131,53.5519507702,609.6 -3.0772410052,53.5505796121,609.6 -3.0717594907,53.5495383493,609.6 -3.0661274586,53.54883799510001,609.6 -3.0604044788,53.5484859565,609.6 -3.0546510767,53.5484859565,609.6 -3.048928097,53.54883799510001,609.6 -3.0432960648,53.5495383493,609.6 -3.037814550299999,53.5505796121,609.6 -3.0325415424,53.5519507702,609.6 -3.0275328393,53.55363732,609.6 -3.0228414607,53.55562141970001,609.6 -3.0185170893,53.5578820774,609.6 -3.0146055459,53.5603953712,609.6 -3.011148304799999,53.5631347019,609.6 -3.0081820531,53.5660710724,609.6 -3.0057383008,53.5691733937,609.6 -3.0038430436,53.572408813,609.6 -3.0025164838,53.5757430602,609.6 -3.001772810899999,53.57914081059999,609.6 -3.0016200463,53.5825660578,609.6 -3.0020599523,53.5859824958,609.6 -3.0030880073,53.5893539031,609.6 -3.0046934478,53.5926445269,609.6 -3.0068593766,53.5958194632,609.6 -3.0095629372,53.5988450274,609.6 -3.0127755514,53.6016891128,609.6 -3.0164632191,53.60432153210001,609.6 -3.0205868758,53.6067143394,609.6 -3.0251028064,53.608842128,609.6 -3.0299631082,53.6106823016,609.6 -3.035116200200001,53.6122153156,609.6 -3.0405073722,53.61342488569999,609.6 -3.0460793689,53.6142981621,609.6 -3.051773001,53.6148258671,609.6 -3.0575277778,53.615002394,609.6 + + + + +
+ + EGRU303B WOODVALE RWY 03 + 533204N 0030543W -
533220N 0030630W -
533320N 0030531W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533304N 0030444W -
533204N 0030543W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0953566667,53.53433488889999,609.6 -3.0789983056,53.5509941389,609.6 -3.0835627936,53.5522709422,609.6 -3.0879157218,53.5537874214,609.6 -3.0920216944,53.55553125,609.6 -3.108372694399999,53.5388743611,609.6 -3.0953566667,53.53433488889999,609.6 + + + + +
+ + EGRU303C WOODVALE RWY 21 + 533745N 0030111W -
533728N 0030024W -
533628N 0030123W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533645N 0030210W -
533745N 0030111W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0196293889,53.6290938333,609.6 -3.0360356111,53.6124486667,609.6 -3.031465676,53.6111705519,609.6 -3.0271083965,53.609652509,609.6 -3.0229993056,53.6079069167,609.6 -3.0065856389,53.6245544167,609.6 -3.0196293889,53.6290938333,609.6 + + + + +
+ + EGRU303D WOODVALE RWY 08 + 533358N 0030816W -
533430N 0030825W -
533439N 0030647W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533408N 0030633W -
533358N 0030816W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1378758889,53.5660964167,609.6 -3.1091354444,53.56891102779999,609.6 -3.1108744368,53.5717451964,609.6 -3.112175241400001,53.57466145050001,609.6 -3.1130270833,53.57763583329999,609.6 -3.140312638899999,53.5749635278,609.6 -3.1378758889,53.5660964167,609.6 + + + + +
+ + EGRU303E WOODVALE RWY 26 + 533526N 0025847W -
533454N 0025838W -
533446N 0030006W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533454N 0030327W to
533518N 0030010W -
533526N 0025847W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9796778611,53.59060158329999,609.6 -3.002726,53.58837175,609.6 -3.0019410534,53.5853908477,609.6 -3.0016131184,53.58237989359999,609.6 -3.0017448056,53.5793636389,609.6 -2.9772401944,53.5817345,609.6 -2.9796778611,53.59060158329999,609.6 + + + + +
+ + EGRU304A BLACKPOOL + A circle, 2.5 NM radius, centred at 534618N 0030143W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0286111111,53.813265525,609.6 -3.0350967314,53.813087897,609.6 -3.041526855299999,53.8125565327,609.6 -3.0478464658,53.81167597889999,609.6 -3.0540014992,53.8104537697,609.6 -3.0599393125,53.80890036139999,609.6 -3.065609135799999,53.807029043,609.6 -3.0709625102,53.8048558208,609.6 -3.0759537036,53.80239928089999,609.6 -3.080540103200001,53.79968042910001,609.6 -3.084682579699999,53.7967225097,609.6 -3.0883458215,53.7935508061,609.6 -3.0914986345,53.79019242289999,609.6 -3.0941142068,53.7866760536,609.6 -3.0961703336,53.78303173399999,609.6 -3.0976496038,53.7792905852,609.6 -3.098539543299999,53.7754845467,609.6 -3.0988327171,53.7716461032,609.6 -3.0985267866,53.7678080074,609.6 -3.0976245247,53.764003,609.6 -3.0961337862,53.76026353069999,609.6 -3.0940674357,53.7566214818,609.6 -3.0914432325,53.75310789700001,609.6 -3.088283675,53.7497527174,609.6 -3.084615805299999,53.74658452719999,609.6 -3.0804709746,53.7436303116,609.6 -3.0758845751,53.7409152277,609.6 -3.070895735700001,53.7384623916,609.6 -3.0655469893,53.7362926829,609.6 -3.0598839103,53.734424568,609.6 -3.0539547281,53.7328739443,609.6 -3.0478099183,53.7316540056,609.6 -3.0415017762,53.73077513130001,609.6 -3.0350839746,53.7302447983,609.6 -3.0286111111,53.7300675179,609.6 -3.0221382476,53.7302447983,609.6 -3.015720446,53.73077513130001,609.6 -3.0094123039,53.7316540056,609.6 -3.0032674941,53.7328739443,609.6 -2.997338311900001,53.734424568,609.6 -2.9916752329,53.7362926829,609.6 -2.986326486499999,53.7384623916,609.6 -2.981337647200001,53.7409152277,609.6 -2.9767512476,53.7436303116,609.6 -2.972606417000001,53.74658452719999,609.6 -2.9689385472,53.7497527174,609.6 -2.9657789898,53.75310789700001,609.6 -2.963154786600001,53.7566214818,609.6 -2.961088436,53.76026353069999,609.6 -2.9595976975,53.764003,609.6 -2.9586954356,53.7678080074,609.6 -2.9583895052,53.7716461032,609.6 -2.9586826789,53.7754845467,609.6 -2.9595726185,53.7792905852,609.6 -2.9610518886,53.78303173399999,609.6 -2.9631080155,53.7866760536,609.6 -2.9657235877,53.79019242289999,609.6 -2.9688764007,53.7935508061,609.6 -2.972539642500001,53.7967225097,609.6 -2.976682118999999,53.79968042910001,609.6 -2.9812685186,53.80239928089999,609.6 -2.986259712,53.8048558208,609.6 -2.991613086400001,53.807029043,609.6 -2.9972829098,53.80890036139999,609.6 -3.003220723,53.8104537697,609.6 -3.0093757564,53.81167597889999,609.6 -3.0156953669,53.8125565327,609.6 -3.0221254908,53.813087897,609.6 -3.0286111111,53.813265525,609.6 + + + + +
+ + EGRU304B BLACKPOOL RWY 10 + 534617N 0030708W -
534649N 0030704W -
534646N 0030551W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534613N 0030556W -
534617N 0030708W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1188944444,53.7713694444,609.6 -3.0987998889,53.7704148056,609.6 -3.0987721547,53.7734150578,609.6 -3.0983793941,53.7764063199,609.6 -3.097623583299999,53.7793730278,609.6 -3.1176611111,53.780325,609.6 -3.1188944444,53.7713694444,609.6 + + + + +
+ + EGRU304C BLACKPOOL RWY 28 + 534618N 0025618W -
534546N 0025622W -
534549N 0025735W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534622N 0025730W -
534618N 0025618W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.93825,53.7716805556,609.6 -2.9584088889,53.7726654167,609.6 -2.9584724548,53.769665424,609.6 -2.9589008064,53.7666759456,609.6 -2.959691638899999,53.7637125278,609.6 -2.9394777778,53.762725,609.6 -2.93825,53.7716805556,609.6 + + + + +
+ + EGRU304D BLACKPOOL RWY 13 + 534750N 0030625W -
534816N 0030552W -
534752N 0030459W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534725N 0030529W -
534750N 0030625W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.106925,53.7973527778,609.6 -3.0913692778,53.7903458056,609.6 -3.0889268368,53.79298410559999,609.6 -3.0861684105,53.7955109174,609.6 -3.0831083889,53.797913,609.6 -3.097725,53.8044972222,609.6 -3.106925,53.7973527778,609.6 + + + + +
+ + EGRU304E BLACKPOOL RWY 31 + 534444N 0025801W -
534418N 0025834W -
534427N 0025854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534618N 0030143W to
534451N 0025817W -
534444N 0025801W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9668805556,53.7454194444,609.6 -2.9714730833,53.74749825,609.6 -2.9745715778,53.7451145435,609.6 -2.9779523219,53.7428697567,609.6 -2.9815976111,53.7407756111,609.6 -2.9760666667,53.7382722222,609.6 -2.9668805556,53.7454194444,609.6 + + + + +
+ + EGRU305A HAWARDEN + A circle, 2.5 NM radius, centred at 531041N 0025840W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9777777778,53.2196585709,609.6 -2.9841733813,53.2194809288,609.6 -2.9905142623,53.2189495226,609.6 -2.9967461703,53.21806889900001,609.6 -3.0028157954,53.2168465921,609.6 -3.0086712274,53.2152930587,609.6 -3.0142624035,53.2134215879,609.6 -3.0195415387,53.2112481864,609.6 -3.0244635363,53.2087914411,609.6 -3.0289863748,53.2060723582,609.6 -3.0330714673,53.2031141832,609.6 -3.0366839906,53.1999422005,609.6 -3.0397931814,53.19658351619999,609.6 -3.0423725966,53.1930668254,609.6 -3.044400336399999,53.1894221661,609.6 -3.0458592271,53.1856806614,609.6 -3.0467369634,53.18187425350001,609.6 -3.0470262088,53.1780354301,609.6 -3.0467246526,53.1741969468,609.6 -3.0458350247,53.1703915479,609.6 -3.0443650667,53.16665168659999,609.6 -3.0423274606,53.16300924920001,609.6 -3.0397397161,53.1594952831,609.6 -3.0366240167,53.1561397334,609.6 -3.0330070272,53.1529711887,609.6 -3.0289196629,53.1500166378,609.6 -3.0243968244,53.1473012419,609.6 -3.0194770986,53.1448481206,609.6 -3.0142024296,53.1426781572,609.6 -3.0086177621,53.140809821,609.6 -3.0027706593,53.1392590123,609.6 -2.9967109005,53.1380389272,609.6 -2.9904900599,53.13715994700001,609.6 -2.984161070499999,53.13662954979999,609.6 -2.9777777778,53.1364522479,609.6 -2.971394484999999,53.13662954979999,609.6 -2.9650654957,53.13715994700001,609.6 -2.958844655,53.1380389272,609.6 -2.9527848963,53.1392590123,609.6 -2.9469377935,53.140809821,609.6 -2.9413531259,53.1426781572,609.6 -2.936078457,53.1448481206,609.6 -2.9311587312,53.1473012419,609.6 -2.9266358927,53.1500166378,609.6 -2.9225485284,53.1529711887,609.6 -2.9189315388,53.1561397334,609.6 -2.9158158395,53.1594952831,609.6 -2.913228095,53.16300924920001,609.6 -2.9111904889,53.16665168659999,609.6 -2.9097205308,53.1703915479,609.6 -2.9088309029,53.1741969468,609.6 -2.9085293468,53.1780354301,609.6 -2.9088185922,53.18187425350001,609.6 -2.9096963285,53.1856806614,609.6 -2.911155219099999,53.1894221661,609.6 -2.9131829589,53.1930668254,609.6 -2.9157623742,53.19658351619999,609.6 -2.918871565,53.1999422005,609.6 -2.9224840883,53.2031141832,609.6 -2.9265691808,53.2060723582,609.6 -2.9310920193,53.2087914411,609.6 -2.936014016900001,53.2112481864,609.6 -2.941293152,53.2134215879,609.6 -2.9468843281,53.2152930587,609.6 -2.952739760200001,53.2168465921,609.6 -2.9588093852,53.21806889900001,609.6 -2.9650412933,53.2189495226,609.6 -2.9713821742,53.2194809288,609.6 -2.9777777778,53.2196585709,609.6 + + + + +
+ + EGRU305B HAWARDEN RWY 04 + 530811N 0030141W -
530832N 0030222W -
530859N 0030143W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to
530838N 0030102W -
530811N 0030141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.028075,53.13637500000001,609.6 -3.0172443611,53.1438768889,609.6 -3.021239603,53.1456745645,609.6 -3.025009308800001,53.1476405689,609.6 -3.0285338889,53.1497646944,609.6 -3.0393527778,53.14226944440001,609.6 -3.028075,53.13637500000001,609.6 + + + + +
+ + EGRU305C HAWARDEN RWY 22 + 531311N 0025538W -
531250N 0025457W -
531223N 0025537W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 531041N 0025840W to
531244N 0025618W -
531311N 0025538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9271138889,53.2198527778,609.6 -2.938205555600001,53.21220305559999,609.6 -2.9342095663,53.21040064769999,609.6 -2.930440711300001,53.2084299101,609.6 -2.9269186111,53.2063011111,609.6 -2.9158138889,53.21395833329999,609.6 -2.9271138889,53.2198527778,609.6 + + + + +
+ + EGRU306A WARTON + A circle, 2.5 NM radius, centred at 534442N 0025300W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8834361111,53.7866240444,609.6 -2.889917622,53.7864464157,609.6 -2.8963436718,53.7859150496,609.6 -2.9026592785,53.78503449269999,609.6 -2.9088104129,53.78381227900001,609.6 -2.9147444653,53.78225886519999,609.6 -2.9204106983,53.78038754,609.6 -2.925760683500001,53.7782143098,609.6 -2.9307487181,53.7757577607,609.6 -2.935332215999999,53.7730388986,609.6 -2.9394720729,53.77008096779999,609.6 -2.9431329994,53.76690925180001,609.6 -2.946283821,53.7635508551,609.6 -2.9488977427,53.7600344714,609.6 -2.9509525737,53.75639013669999,609.6 -2.9524309136,53.752648972,609.6 -2.9533202961,53.7488429169,609.6 -2.9536132906,53.7450044565,609.6 -2.9533075598,53.7411663433,609.6 -2.9524058748,53.73736131839999,609.6 -2.950916085,53.7336218315,609.6 -2.9488510467,53.7299797653,609.6 -2.9462285079,53.72646616339999,609.6 -2.9430709527,53.7231109672,609.6 -2.9394054057,53.7199427611,609.6 -2.9352631985,53.71698853049999,609.6 -2.9306797005,53.7142734326,609.6 -2.9256940162,53.7118205837,609.6 -2.9203486515,53.70965086350001,609.6 -2.9146891521,53.70778273869999,609.6 -2.9087637168,53.7062321067,609.6 -2.902622789700001,53.7050121615,609.6 -2.896318633,53.7041332824,609.6 -2.8899048857,53.7036029465,609.6 -2.8834361111,53.7034256651,609.6 -2.8769673366,53.7036029465,609.6 -2.8705535893,53.7041332824,609.6 -2.8642494325,53.7050121615,609.6 -2.8581085054,53.7062321067,609.6 -2.8521830701,53.70778273869999,609.6 -2.846523570700001,53.70965086350001,609.6 -2.841178206,53.7118205837,609.6 -2.8361925217,53.7142734326,609.6 -2.8316090238,53.71698853049999,609.6 -2.8274668166,53.7199427611,609.6 -2.8238012695,53.7231109672,609.6 -2.8206437143,53.72646616339999,609.6 -2.8180211755,53.7299797653,609.6 -2.8159561372,53.7336218315,609.6 -2.8144663475,53.73736131839999,609.6 -2.813564662400001,53.7411663433,609.6 -2.8132589317,53.7450044565,609.6 -2.8135519261,53.7488429169,609.6 -2.8144413086,53.752648972,609.6 -2.8159196485,53.75639013669999,609.6 -2.8179744795,53.7600344714,609.6 -2.8205884012,53.7635508551,609.6 -2.8237392229,53.76690925180001,609.6 -2.8274001493,53.77008096779999,609.6 -2.8315400062,53.7730388986,609.6 -2.836123504100001,53.7757577607,609.6 -2.8411115387,53.7782143098,609.6 -2.846461524,53.78038754,609.6 -2.8521277569,53.78225886519999,609.6 -2.8580618093,53.78381227900001,609.6 -2.8642129437,53.78503449269999,609.6 -2.8705285504,53.7859150496,609.6 -2.8769546003,53.7864464157,609.6 -2.8834361111,53.7866240444,609.6 + + + + +
+ + EGRU306B WARTON RWY 07 + 534322N 0025811W -
534353N 0025828W -
534409N 0025707W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to
534339N 0025649W -
534322N 0025811W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9695861111,53.7228194444,609.6 -2.9469941389,53.72740525,609.6 -2.9489722681,53.730166133,609.6 -2.9506099817,53.7330043435,609.6 -2.9518986944,53.7359051389,609.6 -2.974475,53.7313222222,609.6 -2.9695861111,53.7228194444,609.6 + + + + +
+ + EGRU306C WARTON RWY 25 + 534602N 0024750W -
534531N 0024732W -
534515N 0024854W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 534442N 0025300W to
534545N 0024911W -
534602N 0024750W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7972166667,53.7671638889,609.6 -2.8198246111,53.7626105556,609.6 -2.8178532713,53.75984722719999,609.6 -2.8162233905,53.7570068727,609.6 -2.8149433889,53.7541042778,609.6 -2.7923166667,53.7586611111,609.6 -2.7972166667,53.7671638889,609.6 + + + + +
+ + EGRU307A LIVERPOOL + A circle, 2.5 NM radius, centred at 532001N 0025059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8497222222,53.3752130345,609.6 -2.8561411049,53.3750353962,609.6 -2.862505065000001,53.3745040011,609.6 -2.8687596537,53.3736233958,609.6 -2.8748513663,53.3724011146,609.6 -2.8807281029,53.3708476142,609.6 -2.8863396181,53.3689761835,609.6 -2.8916379523,53.3668028293,609.6 -2.8965778448,53.364346138,609.6 -2.901117121,53.361627116,609.6 -2.9052170537,53.3586690083,609.6 -2.9088426935,53.355497099,609.6 -2.9119631657,53.3521384939,609.6 -2.9145519318,53.3486218877,609.6 -2.916587013,53.34497731769999,609.6 -2.9180511743,53.3412359065,609.6 -2.9189320668,53.3374295957,609.6 -2.9192223284,53.333590872,609.6 -2.9189196412,53.3297524905,609.6 -2.9180267463,53.32594719439999,609.6 -2.9165514144,53.322207436,609.6 -2.9145063748,53.3185651006,609.6 -2.9119092018,53.3150512345,609.6 -2.9087821604,53.31169578200001,609.6 -2.9051520127,53.3085273302,609.6 -2.9010497869,53.3055728673,609.6 -2.896510510700001,53.3028575532,609.6 -2.8915729112,53.30040450669999,609.6 -2.8862790848,53.29823461,609.6 -2.880674139,53.29636633179999,609.6 -2.8748058092,53.2948155716,609.6 -2.868724055,53.2935955249,609.6 -2.8624806369,53.29271657250001,609.6 -2.8561286793,53.2921861921,609.6 -2.8497222222,53.2920088958,609.6 -2.8433157651,53.2921861921,609.6 -2.8369638075,53.29271657250001,609.6 -2.8307203894,53.2935955249,609.6 -2.8246386352,53.2948155716,609.6 -2.8187703055,53.29636633179999,609.6 -2.8131653596,53.29823461,609.6 -2.8078715332,53.30040450669999,609.6 -2.8029339337,53.3028575532,609.6 -2.7983946575,53.3055728673,609.6 -2.7942924318,53.3085273302,609.6 -2.7906622841,53.31169578200001,609.6 -2.7875352426,53.3150512345,609.6 -2.7849380696,53.3185651006,609.6 -2.78289303,53.322207436,609.6 -2.7814176981,53.32594719439999,609.6 -2.7805248032,53.3297524905,609.6 -2.7802221161,53.333590872,609.6 -2.7805123776,53.3374295957,609.6 -2.7813932701,53.3412359065,609.6 -2.7828574314,53.34497731769999,609.6 -2.7848925127,53.3486218877,609.6 -2.7874812787,53.3521384939,609.6 -2.7906017509,53.355497099,609.6 -2.7942273907,53.3586690083,609.6 -2.7983273235,53.361627116,609.6 -2.8028665997,53.364346138,609.6 -2.8078064921,53.3668028293,609.6 -2.8131048264,53.3689761835,609.6 -2.8187163415,53.3708476142,609.6 -2.8245930782,53.3724011146,609.6 -2.8306847907,53.3736233958,609.6 -2.8369393794,53.3745040011,609.6 -2.8433033395,53.3750353962,609.6 -2.8497222222,53.3752130345,609.6 + + + + +
+ + EGRU307B LIVERPOOL RWY 09 + 531930N 0025625W -
532002N 0025629W -
532006N 0025509W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to
531933N 0025505W -
531930N 0025625W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9402555556,53.3249333333,609.6 -2.9180339167,53.3259700278,609.6 -2.9187785016,53.3289367765,609.6 -2.9191640932,53.3319279325,609.6 -2.9191886111,53.3349279444,609.6 -2.941399999999999,53.3338916667,609.6 -2.9402555556,53.3249333333,609.6 + + + + +
+ + EGRU307C LIVERPOOL RWY 27 + 532032N 0024530W -
532000N 0024526W -
531956N 0024649W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532001N 0025059W to
532029N 0024653W -
532032N 0024530W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7584444444,53.34230277779999,609.6 -2.7814016667,53.3412629167,609.6 -2.7806603436,53.3382957709,609.6 -2.7802782982,53.3353043619,609.6 -2.7802574444,53.33230425,609.6 -2.7572916667,53.3333444444,609.6 -2.7584444444,53.34230277779999,609.6 + + + + +
+ + EGRU308A MANCHESTER + A circle, 2.5 NM radius, centred at 532113N 0021630W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2749509722,53.3953507267,609.6 -2.2813728845,53.39517308880001,609.6 -2.2877398481,53.3946416951,609.6 -2.2939973885,53.3937610922,609.6 -2.3000919755,53.3925388144,609.6 -2.3059714848,53.3909853182,609.6 -2.3115856468,53.3891138927,609.6 -2.3168864796,53.38694054449999,609.6 -2.3218287009,53.38448386030001,609.6 -2.3263701163,53.38176484609999,609.6 -2.3304719804,53.3788067471,609.6 -2.3340993272,53.3756348473,609.6 -2.3372212675,53.3722762524,609.6 -2.3398112505,53.3687596571,609.6 -2.3418472871,53.3651150987,609.6 -2.3433121343,53.3613736996,609.6 -2.3441934376,53.35756740130001,609.6 -2.3444838314,53.35372869059999,609.6 -2.344180997,53.34989032229999,609.6 -2.3432876769,53.3460850394,609.6 -2.3418116456,53.3423452944,609.6 -2.3397656387,53.33870297209999,609.6 -2.3371672386,53.335189119,609.6 -2.3340387211,53.331833679,609.6 -2.330406861,53.3286652393,609.6 -2.3263027012,53.3257107877,609.6 -2.3217612858,53.32299548419999,609.6 -2.3168213602,53.3205424474,609.6 -2.3115250407,53.3183725594,609.6 -2.3059174558,53.3165042887,609.6 -2.3000463636,53.3149535347,609.6 -2.2939617469,53.3137334931,609.6 -2.2877153906,53.3128545442,609.6 -2.2813604439,53.312324166,609.6 -2.2749509722,53.3121468705,609.6 -2.2685415005,53.312324166,609.6 -2.2621865539,53.3128545442,609.6 -2.2559401975,53.3137334931,609.6 -2.2498555809,53.3149535347,609.6 -2.2439844887,53.3165042887,609.6 -2.2383769038,53.3183725594,609.6 -2.2330805842,53.3205424474,609.6 -2.2281406587,53.32299548419999,609.6 -2.2235992433,53.3257107877,609.6 -2.2194950835,53.3286652393,609.6 -2.2158632233,53.331833679,609.6 -2.2127347058,53.335189119,609.6 -2.2101363058,53.33870297209999,609.6 -2.2080902988,53.3423452944,609.6 -2.2066142676,53.3460850394,609.6 -2.2057209474,53.34989032229999,609.6 -2.2054181131,53.35372869059999,609.6 -2.2057085069,53.35756740130001,609.6 -2.2065898101,53.3613736996,609.6 -2.2080546573,53.3651150987,609.6 -2.210090694,53.3687596571,609.6 -2.2126806769,53.3722762524,609.6 -2.2158026173,53.3756348473,609.6 -2.2194299641,53.3788067471,609.6 -2.2235318281,53.38176484609999,609.6 -2.2280732435,53.38448386030001,609.6 -2.2330154648,53.38694054449999,609.6 -2.2383162976,53.3891138927,609.6 -2.2439304597,53.3909853182,609.6 -2.2498099689,53.3925388144,609.6 -2.255904556,53.3937610922,609.6 -2.2621620964,53.3946416951,609.6 -2.2685290599,53.39517308880001,609.6 -2.2749509722,53.3953507267,609.6 + + + + +
+ + EGRU308B MANCHESTER RWY 05L + 531857N 0022029W -
531922N 0022103W -
531953N 0022000W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
531928N 0021926W -
531857N 0022029W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3414111111,53.31581111109999,609.6 -2.3238734167,53.324307,609.6 -2.3273308396,53.3264781521,609.6 -2.3304832641,53.32881098330001,609.6 -2.3333465833,53.3312738611,609.6 -2.3508361111,53.3228,609.6 -2.3414111111,53.31581111109999,609.6 + + + + +
+ + EGRU308C MANCHESTER RWY 23R + 532335N 0021220W -
532310N 0021146W -
532235N 0021259W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
532300N 0021333W -
532335N 0021220W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2055305556,53.3930222222,609.6 -2.2257580556,53.3832712778,609.6 -2.2223686207,53.3810587658,609.6 -2.2192198687,53.3787240926,609.6 -2.2163605833,53.3762599167,609.6 -2.1960833333,53.38603333330001,609.6 -2.2055305556,53.3930222222,609.6 + + + + +
+ + EGRU308D MANCHESTER RWY 05R + 531801N 0022151W -
531826N 0022225W -
531942N 0021948W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532113N 0021630W to
531919N 0021910W -
531801N 0022151W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3642722222,53.3002166667,609.6 -2.3194853889,53.3219233611,609.6 -2.3232527059,53.32391940340001,609.6 -2.326738245,53.3260924911,609.6 -2.3299518889,53.3284110278,609.6 -2.3736972222,53.30720555559999,609.6 -2.3642722222,53.3002166667,609.6 + + + + +
+ + EGRU309A MANCHESTER BARTON + 532618N 0022327W thence clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532749N 0022008W -
532638N 0022258W -
532618N 0022327W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3907305556,53.43829722219999,609.6 -2.3827777778,53.44388888890001,609.6 -2.3355777778,53.4635694444,609.6 -2.3343558953,53.4669212271,609.6 -2.3338295699,53.4703398171,609.6 -2.3338945616,53.473772581,609.6 -2.3345503253,53.4771831975,609.6 -2.3357900617,53.48053557090001,609.6 -2.3376007831,53.48379421360001,609.6 -2.3399634458,53.4869246223,609.6 -2.3428531463,53.4898936441,609.6 -2.3462393808,53.49266982850001,609.6 -2.3500863655,53.4952237618,609.6 -2.3543534126,53.49752838000001,609.6 -2.3589953605,53.4995592571,609.6 -2.3639630523,53.50129486489999,609.6 -2.3692038574,53.502716803,609.6 -2.3746622316,53.5038099946,609.6 -2.3802803087,53.5045628477,609.6 -2.3859985173,53.5049673785,609.6 -2.391756217,53.5050192971,609.6 -2.3974923454,53.50471805269999,609.6 -2.4031460708,53.5040668403,609.6 -2.4086574411,53.5030725655,609.6 -2.4139680243,53.5017457719,609.6 -2.4190215316,53.5001005278,609.6 -2.4237644171,53.4981542763,609.6 -2.4281464477,53.49592764920001,609.6 -2.4321212367,53.4934442471,609.6 -2.4356467354,53.490730388,609.6 -2.4386856781,53.48781482670001,609.6 -2.4412059746,53.4847284494,609.6 -2.4431810468,53.48150394459999,609.6 -2.4445901066,53.47817545670001,609.6 -2.4454183711,53.4747782227,609.6 -2.4456572136,53.4713481991,609.6 -2.4453042492,53.4679216808,609.6 -2.4443633537,53.464534917,609.6 -2.4428446174,53.4612237276,609.6 -2.4407642317,53.4580231253,609.6 -2.4381443133,53.4549669457,609.6 -2.4350126656,53.4520874903,609.6 -2.4314024809,53.4494151868,609.6 -2.4273519867,53.4469782683,609.6 -2.4229040406,53.4448024765,609.6 -2.4181056758,53.442910791,609.6 -2.4130076057,53.4413231879,609.6 -2.407663689,53.4400564305,609.6 -2.4021303634,53.4391238927,609.6 -2.3964660531,53.4385354193,609.6 -2.3907305556,53.43829722219999,609.6 + + + + +
+ + EGRU309B MANCHESTER BARTON RWY 02 + 532531N 0022405W -
532540N 0022457W -
532626N 0022437W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532619N 0022344W -
532531N 0022405W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.401275,53.4254111111,609.6 -2.395574,53.4384753889,609.6 -2.4005470392,53.4389250988,609.6 -2.4054320863,53.43964046000001,609.6 -2.4101894444,53.4406156667,609.6 -2.4158305556,53.42767777779999,609.6 -2.401275,53.4254111111,609.6 + + + + +
+ + EGRU309C MANCHESTER BARTON RWY 20 + 533107N 0022234W -
533059N 0022141W -
533008N 0022204W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
533016N 0022256W -
533107N 0022234W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3760861111,53.5186583333,609.6 -2.3822588889,53.5045544444,609.6 -2.3773016223,53.5040188623,609.6 -2.3724457077,53.5032188044,609.6 -2.3677307778,53.5021608056,609.6 -2.3614972222,53.51639166670001,609.6 -2.3760861111,53.5186583333,609.6 + + + + +
+ + EGRU309D MANCHESTER BARTON RWY 08L + 532741N 0022809W -
532813N 0022816W -
532820N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532748N 0022637W -
532741N 0022809W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.469125,53.46131111110001,609.6 -2.4437155833,53.4632409444,609.6 -2.4447561923,53.466179194,609.6 -2.4453488031,53.469161453,609.6 -2.4454885,53.4721634444,609.6 -2.4710111111,53.47022499999999,609.6 -2.469125,53.46131111110001,609.6 + + + + +
+ + EGRU309E MANCHESTER BARTON RWY 26R + 532856N 0021843W -
532824N 0021836W -
532817N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532850N 0022009W -
532856N 0021843W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.312025,53.4822083333,609.6 -2.3359380833,53.4804198611,609.6 -2.3348219146,53.4774914143,609.6 -2.334152951,53.4745148593,609.6 -2.3339365278,53.4715144444,609.6 -2.3101361111,53.4732944444,609.6 -2.312025,53.4822083333,609.6 + + + + +
+ + EGRU309F MANCHESTER BARTON RWY 08R + 532740N 0022805W -
532812N 0022812W -
532819N 0022644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532747N 0022637W -
532740N 0022805W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4681555556,53.46114444439999,609.6 -2.4436079722,53.4629968056,609.6 -2.4446857783,53.46592982210001,609.6 -2.4453162818,53.4689088672,609.6 -2.4454942778,53.4719096944,609.6 -2.4700277778,53.4700583333,609.6 -2.4681555556,53.46114444439999,609.6 + + + + +
+ + EGRU309G MANCHESTER BARTON RWY 26L + 532855N 0021841W -
532823N 0021834W -
532816N 0022002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532848N 0022009W -
532855N 0021841W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3112611111,53.4819472222,609.6 -2.3358037778,53.4801236111,609.6 -2.3347330633,53.47718953730001,609.6 -2.3341101379,53.4742098286,609.6 -2.3339399722,53.47120875,609.6 -2.3093833333,53.4730333333,609.6 -2.3112611111,53.4819472222,609.6 + + + + +
+ + EGRU309H MANCHESTER BARTON RWY 14 + 533006N 0022654W -
533029N 0022616W -
532956N 0022518W thence anti-clockwise by the arc of a circle radius 2 NM centred on 532818N 0022323W to
532934N 0022558W -
533006N 0022654W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4483,53.5017388889,609.6 -2.4327602222,53.4927476389,609.6 -2.4293792212,53.49497990039999,609.6 -2.4256737115,53.4970209071,609.6 -2.4216739444,53.4988539444,609.6 -2.4377944444,53.5081833333,609.6 -2.4483,53.5017388889,609.6 + + + + +
+ + EGRU309I MANCHESTER BARTON RWY 32 + 532635N 0021932W -
532612N 0022010W -
532708N 0022146W -
532727N 0022101W -
532635N 0021932W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3255083333,53.44306944440001,609.6 -2.3502631944,53.4574508611,609.6 -2.3628273056,53.4522123889,609.6 -2.3359944444,53.43662777779999,609.6 -2.3255083333,53.44306944440001,609.6 + + + + +
+ + EGRU310A LEEDS BRADFORD + A circle, 2.5 NM radius, centred at 535158N 0013939W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6607694444,53.90762320009999,609.6 -1.6672696727,53.9074455742,609.6 -1.6737142792,53.90691421660001,609.6 -1.680048122,53.9060336738,609.6 -1.6862170157,53.9048114799,609.6 -1.6921681977,53.90325809139999,609.6 -1.6978507839,53.9013867969,609.6 -1.7032162058,53.89921360300001,609.6 -1.7082186283,53.8967570955,609.6 -1.7128153425,53.8940382802,609.6 -1.7169671311,53.8910804012,609.6 -1.7206386033,53.8879087416,609.6 -1.7237984952,53.884550406,609.6 -1.7264199347,53.8810340875,609.6 -1.728480668,53.8773898217,609.6 -1.7299632451,53.87364872919999,609.6 -1.7308551647,53.8698427491,609.6 -1.7311489757,53.8660043658,609.6 -1.7308423351,53.8621663314,609.6 -1.7299380227,53.858361386,609.6 -1.7284439118,53.8546219788,609.6 -1.7263728964,53.85097999159999,609.6 -1.7237427766,53.8474664672,609.6 -1.7205761018,53.8441113463,609.6 -1.7168999752,53.84094321240001,609.6 -1.712745819,53.83798905,609.6 -1.7081491048,53.83527401569999,609.6 -1.7031490498,53.8328212248,609.6 -1.6977882823,53.8306515566,609.6 -1.692112479,53.8287834768,609.6 -1.6861699773,53.8272328825,609.6 -1.6800113658,53.8260129671,609.6 -1.6736890567,53.8251341097,609.6 -1.6672568431,53.8246037868,609.6 -1.6607694444,53.8244265098,609.6 -1.6542820458,53.8246037868,609.6 -1.6478498321,53.8251341097,609.6 -1.6415275231,53.8260129671,609.6 -1.6353689116,53.8272328825,609.6 -1.6294264099,53.8287834768,609.6 -1.6237506065,53.8306515566,609.6 -1.6183898391,53.8328212248,609.6 -1.6133897841,53.83527401569999,609.6 -1.6087930699,53.83798905,609.6 -1.6046389137,53.84094321240001,609.6 -1.6009627871,53.8441113463,609.6 -1.5977961123,53.8474664672,609.6 -1.5951659925,53.85097999159999,609.6 -1.5930949771,53.8546219788,609.6 -1.5916008662,53.858361386,609.6 -1.5906965538,53.8621663314,609.6 -1.5903899132,53.8660043658,609.6 -1.5906837242,53.8698427491,609.6 -1.5915756438,53.87364872919999,609.6 -1.5930582209,53.8773898217,609.6 -1.5951189542,53.8810340875,609.6 -1.5977403937,53.884550406,609.6 -1.6009002856,53.8879087416,609.6 -1.6045717577,53.8910804012,609.6 -1.6087235464,53.8940382802,609.6 -1.6133202606,53.8967570955,609.6 -1.618322683,53.89921360300001,609.6 -1.623688105,53.9013867969,609.6 -1.6293706912,53.90325809139999,609.6 -1.6353218732,53.9048114799,609.6 -1.6414907669,53.9060336738,609.6 -1.6478246097,53.90691421660001,609.6 -1.6542692162,53.9074455742,609.6 -1.6607694444,53.90762320009999,609.6 + + + + +
+ + EGRU310B LEEDS BRADFORD RWY 14 + 535406N 0014333W -
535428N 0014253W -
535359N 0014208W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to
535337N 0014249W -
535406N 0014333W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7258722222,53.90164444440001,609.6 -1.7134789444,53.89360152779999,609.6 -1.7099776463,53.8957754389,609.6 -1.7062197951,53.89779451370001,609.6 -1.7022249444,53.8996482222,609.6 -1.7146083333,53.90768611110001,609.6 -1.7258722222,53.90164444440001,609.6 + + + + +
+ + EGRU310C LEEDS BRADFORD RWY 32 + 534948N 0013543W -
534927N 0013624W -
534957N 0013710W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535158N 0013939W to
535018N 0013629W -
534948N 0013543W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5953916667,53.8301222222,609.6 -1.6081265,53.8384270556,609.6 -1.6116280666,53.8362559837,609.6 -1.6153847414,53.834239724,609.6 -1.619377,53.83238875,609.6 -1.6066305556,53.82407777779999,609.6 -1.5953916667,53.8301222222,609.6 + + + + +
+ + EGRU311A SHERBURN-IN-ELMET + 534837N 0011510W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534837N 0011510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2527638889,53.8102666667,609.6 -1.2571224026,53.80797806930001,609.6 -1.2610571872,53.8054348301,609.6 -1.2645260612,53.8026642646,609.6 -1.2674918691,53.79969612469999,609.6 -1.2699228782,53.7965622774,609.6 -1.2717931161,53.7932963613,609.6 -1.2730826444,53.789933425,609.6 -1.2737777682,53.7865095498,609.6 -1.2738711768,53.7830614618,609.6 -1.2733620161,53.779626138,609.6 -1.2722558913,53.77624040969999,609.6 -1.2705648008,53.7729405674,609.6 -1.2683070016,53.7697619731,609.6 -1.2655068083,53.7667386813,609.6 -1.2621943278,53.7639030758,609.6 -1.2584051335,53.7612855237,609.6 -1.2541798811,53.7589140514,609.6 -1.2495638721,53.75681404629999,609.6 -1.2446065683,53.75500798580001,609.6 -1.2393610627,53.7535151986,609.6 -1.2338835135,53.7523516589,609.6 -1.2282325455,53.7515298163,609.6 -1.2224686263,53.7510584638,609.6 -1.2166534236,53.7509426443,609.6 -1.2108491499,53.7511835969,609.6 -1.2051179016,53.7517787436,609.6 -1.1995209993,53.7527217173,609.6 -1.1941183362,53.7540024286,609.6 -1.1889677411,53.7556071738,609.6 -1.1841243629,53.75751877999999,609.6 -1.1796400828,53.75971678800001,609.6 -1.1755629604,53.7621776702,609.6 -1.1719367193,53.7648750804,609.6 -1.1688002784,53.7677801353,609.6 -1.1661873332,53.7708617218,609.6 -1.1641259915,53.7740868293,609.6 -1.1626384686,53.7774209021,609.6 -1.1617408441,53.7808282085,609.6 -1.1614428842,53.7842722237,609.6 -1.1617479309,53.78771602,609.6 -1.1626528599,53.79112266330001,609.6 -1.1641481077,53.79445560920001,609.6 -1.1662177682,53.7976790953,609.6 -1.168839758,53.8007585255,609.6 -1.1719860481,53.8036608427,609.6 -1.1756111111,53.8063611111,609.6 -1.2527638889,53.8102666667,609.6 + + + + +
+ + EGRU311B SHERBURN-IN-ELMET RWY 01 + 534422N 0011301W -
534426N 0011355W -
534506N 0011346W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534504N 0011251W -
534422N 0011301W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.21695,53.7393833333,609.6 -1.2141693611,53.7510245278,609.6 -1.219247129,53.7509727092,609.6 -1.2243120647,53.7511927928,609.6 -1.2293228333,53.751683,609.6 -1.2319555556,53.7406444444,609.6 -1.21695,53.7393833333,609.6 + + + + +
+ + EGRU311C SHERBURN-IN-ELMET RWY 19 + 535003N 0011234W -
534959N 0011140W -
534827N 0011202W -
534830N 0011257W -
535003N 0011234W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2095805556,53.8342722222,609.6 -1.2157734444,53.8084004444,609.6 -1.2006255278,53.8076328889,609.6 -1.1945416667,53.83301111110001,609.6 -1.2095805556,53.8342722222,609.6 + + + + +
+ + EGRU311D SHERBURN-IN-ELMET RWY 06 + 534533N 0011659W -
534601N 0011727W -
534627N 0011616W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534558N 0011553W -
534533N 0011659W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2829833333,53.7592861111,609.6 -1.2646393333,53.76597425,609.6 -1.267242897,53.76857155940001,609.6 -1.2694385055,53.771297993,609.6 -1.271208,53.77413111109999,609.6 -1.2909194444,53.7669444444,609.6 -1.2829833333,53.7592861111,609.6 + + + + +
+ + EGRU311E SHERBURN-IN-ELMET RWY 24 + 534901N 0010912W -
534834N 0010843W -
534803N 0011008W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534824N 0011054W -
534901N 0010912W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1532638889,53.8170138889,609.6 -1.1817541111,53.8066739167,609.6 -1.1756111111,53.8063611111,609.6 -1.1720433532,53.80366947009999,609.6 -1.1689177222,53.80079386109999,609.6 -1.1453166667,53.8093583333,609.6 -1.1532638889,53.8170138889,609.6 + + + + +
+ + EGRU311F SHERBURN-IN-ELMET RWY 10 + 534728N 0011758W -
534759N 0011745W -
534746N 0011612W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534715N 0011625W -
534728N 0011758W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2993888889,53.7910472222,609.6 -1.2736092222,53.78744880559999,609.6 -1.2728948949,53.79042149509999,609.6 -1.2717308379,53.7933439481,609.6 -1.2701264444,53.7961923611,609.6 -1.2958916667,53.7997888889,609.6 -1.2993888889,53.7910472222,609.6 + + + + +
+ + EGRU311G SHERBURN-IN-ELMET RWY 28 + 534640N 0010821W -
534609N 0010834W -
534620N 0010955W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534652N 0010942W -
534640N 0010821W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1391666667,53.7778166667,609.6 -1.1617503611,53.7809968611,609.6 -1.1624732323,53.77802503190001,609.6 -1.1636452747,53.7751038792,609.6 -1.1652568333,53.7722571667,609.6 -1.1426583333,53.769075,609.6 -1.1391666667,53.7778166667,609.6 + + + + +
+ + EGRU311H SHERBURN-IN-ELMET RWY 10G + 534730N 0011755W -
534801N 0011743W -
534748N 0011611W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534717N 0011625W -
534730N 0011755W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2986611111,53.7915666667,609.6 -1.2734953889,53.7880835278,609.6 -1.2726844522,53.7910487701,609.6 -1.2714251173,53.7939586218,609.6 -1.2697275556,53.7967893611,609.6 -1.2951916667,53.8003138889,609.6 -1.2986611111,53.7915666667,609.6 + + + + +
+ + EGRU311I SHERBURN-IN-ELMET RWY 28G + 534643N 0010818W -
534611N 0010830W -
534623N 0010953W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534654N 0010942W -
534643N 0010818W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1383,53.77850277779999,609.6 -1.1616384444,53.7817617222,609.6 -1.1622457931,53.7787795064,609.6 -1.1633045603,53.7758418658,609.6 -1.1648060278,53.7729727222,609.6 -1.1417666667,53.7697555556,609.6 -1.1383,53.77850277779999,609.6 + + + + +
+ + EGRU312A NETHERTHORPE + A circle, 2 NM radius, centred at 531901N 0011146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1962027778,53.350214989,609.6 -1.2019218329,53.3500384556,609.6 -1.2075801243,53.349510731,609.6 -1.2131175379,53.348637422,609.6 -1.2184752531,53.3474278065,609.6 -1.2235963708,53.34589473450001,609.6 -1.2284265212,53.3440544906,609.6 -1.2329144439,53.3419266197,609.6 -1.2370125336,53.3395337186,609.6 -1.240677346,53.3369011946,609.6 -1.2438700589,53.3340569944,609.6 -1.246556882,53.33103130589999,609.6 -1.2487094133,53.327856237,609.6 -1.2503049366,53.3245654734,609.6 -1.2513266582,53.32119392039999,609.6 -1.2517638795,53.317777332,609.6 -1.251612105,53.3143519312,609.6 -1.2508730844,53.31095402610001,609.6 -1.2495547875,53.3076196243,609.6 -1.2476713144,53.30438405269999,609.6 -1.2452427405,53.3012815831,609.6 -1.2422948993,53.2983450703,609.6 -1.2388591045,53.2956056051,609.6 -1.2349718154,53.2930921862,609.6 -1.2306742488,53.2908314149,609.6 -1.2260119419,53.2888472145,609.6 -1.2210342697,53.2871605784,609.6 -1.2157939244,53.2857893497,609.6 -1.2103463594,53.28474803310001,609.6 -1.2047492055,53.2840476424,609.6 -1.1990616652,53.2836955854,609.6 -1.1933438903,53.2836955854,609.6 -1.18765635,53.2840476424,609.6 -1.1820591962,53.28474803310001,609.6 -1.1766116311,53.2857893497,609.6 -1.1713712859,53.2871605784,609.6 -1.1663936137,53.2888472145,609.6 -1.1617313067,53.2908314149,609.6 -1.1574337402,53.2930921862,609.6 -1.1535464511,53.2956056051,609.6 -1.1501106563,53.2983450703,609.6 -1.147162815,53.3012815831,609.6 -1.1447342412,53.30438405269999,609.6 -1.142850768,53.3076196243,609.6 -1.1415324711,53.31095402610001,609.6 -1.1407934505,53.3143519312,609.6 -1.1406416761,53.317777332,609.6 -1.1410788974,53.32119392039999,609.6 -1.1421006189,53.3245654734,609.6 -1.1436961423,53.327856237,609.6 -1.1458486736,53.33103130589999,609.6 -1.1485354967,53.3340569944,609.6 -1.1517282095,53.3369011946,609.6 -1.155393022,53.3395337186,609.6 -1.1594911116,53.3419266197,609.6 -1.1639790343,53.3440544906,609.6 -1.1688091847,53.34589473450001,609.6 -1.1739303024,53.3474278065,609.6 -1.1792880176,53.348637422,609.6 -1.1848254313,53.349510731,609.6 -1.1904837226,53.3500384556,609.6 -1.1962027778,53.350214989,609.6 + + + + +
+ + EGRU312B NETHERTHORPE RWY 06 + 531712N 0011522W -
531739N 0011552W -
531807N 0011445W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
531740N 0011414W -
531712N 0011522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2560277778,53.2867333333,609.6 -1.2372535278,53.294504,609.6 -1.2404625371,53.2968114135,609.6 -1.2433116277,53.2992826763,609.6 -1.2457775556,53.3018976944,609.6 -1.2645416667,53.2941305556,609.6 -1.2560277778,53.2867333333,609.6 + + + + +
+ + EGRU312C NETHERTHORPE RWY 24 + 532049N 0010813W -
532022N 0010742W -
531955N 0010848W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
532022N 0010918W -
532049N 0010813W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1368916667,53.34685555560001,609.6 -1.1551079444,53.33934775,609.6 -1.1519003867,53.3370379636,609.6 -1.1490541355,53.3345644339,609.6 -1.1465923333,53.3319473333,609.6 -1.1283666667,53.33945833329999,609.6 -1.1368916667,53.34685555560001,609.6 + + + + +
+ + EGRU312D NETHERTHORPE RWY 18 + 532146N 0011236W -
532149N 0011142W -
532101N 0011135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
532058N 0011229W -
532146N 0011236W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2100472222,53.3626888889,609.6 -1.2080307222,53.3494531667,609.6 -1.2030826375,53.3499592268,609.6 -1.1980783779,53.350196059,609.6 -1.1930588056,53.35016175,609.6 -1.1950861111,53.36350277780001,609.6 -1.2100472222,53.3626888889,609.6 + + + + +
+ + EGRU312E NETHERTHORPE RWY 36 + 531617N 0011052W -
531614N 0011146W -
531701N 0011153W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0011146W to
531705N 0011059W -
531617N 0011052W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1811194444,53.2714222222,609.6 -1.1831127778,53.2845884722,609.6 -1.1880312955,53.2840134665,609.6 -1.1930161911,53.28370629,609.6 -1.1980269722,53.2836694444,609.6 -1.1960444444,53.2706083333,609.6 -1.1811194444,53.2714222222,609.6 + + + + +
+ + EGRU313A LEEDS EAST + 534837N 0011510W thence clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
534749N 0010956W thence anti-clockwise by the arc of a circle radius 2 NM centred on 534703N 0011304W to
534823N 0011032W -
534837N 0011510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2527638889,53.8102666667,609.6 -1.1756111111,53.8063611111,609.6 -1.1725646884,53.8041867195,609.6 -1.1698741737,53.8018525338,609.6 -1.16752756,53.7993918007,609.6 -1.1655416667,53.79682222219999,609.6 -1.1597722034,53.7985792559,609.6 -1.1543354207,53.8006786956,609.6 -1.1492480814,53.8030656328,609.6 -1.1445534596,53.8057197929,609.6 -1.1402915157,53.8086186276,609.6 -1.1364985567,53.8117375048,609.6 -1.1332069262,53.8150499175,609.6 -1.130444727,53.8185277071,609.6 -1.12823558,53.8221413022,609.6 -1.1265984186,53.82585996890001,609.6 -1.1255473238,53.8296520715,609.6 -1.1250913997,53.833485341,609.6 -1.1252346899,53.8373271494,609.6 -1.1259761385,53.84114478680001,609.6 -1.1273095927,53.8449057406,609.6 -1.1292238505,53.8485779722,609.6 -1.1317027504,53.8521301907,609.6 -1.1347253046,53.8555321199,609.6 -1.1382658734,53.8587547576,609.6 -1.142294381,53.8617706235,609.6 -1.1467765685,53.8645539948,609.6 -1.1516742846,53.8670811269,609.6 -1.15694581,53.86933045699999,609.6 -1.1625462135,53.8712827894,609.6 -1.1684277362,53.8729214607,609.6 -1.1745402006,53.87423248239999,609.6 -1.1808314416,53.87520466229999,609.6 -1.1872477547,53.8758296999,609.6 -1.1937343584,53.8761022585,609.6 -1.2002358655,53.8760200107,609.6 -1.2066967607,53.8755836588,609.6 -1.2130618783,53.8747969287,609.6 -1.2192768777,53.8736665375,609.6 -1.2252887108,53.87220213620001,609.6 -1.231046079,53.870416226,609.6 -1.2364998728,53.8683240512,609.6 -1.2416035943,53.8659434677,609.6 -1.2463137542,53.8632947898,609.6 -1.2505902441,53.8604006154,609.6 -1.254396678,53.8572856321,609.6 -1.2577007011,53.8539764054,609.6 -1.260474264,53.8505011509,609.6 -1.262693858,53.84688949259999,609.6 -1.2643407125,53.8431722097,609.6 -1.2654009498,53.8393809731,609.6 -1.2658656989,53.8355480755,609.6 -1.2657311656,53.8317061553,609.6 -1.2649986589,53.8278879192,609.6 -1.2636745748,53.82412586309999,609.6 -1.2617703363,53.8204519965,609.6 -1.2593022908,53.8168975701,609.6 -1.2562915665,53.8134928111,609.6 -1.2527638889,53.8102666667,609.6 + + + + +
+ + EGRU313B LEEDS EAST RWY 06 + 534803N 0011546W -
534829N 0011617W -
534851N 0011525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
534837N 0011510W -
534835N 0011429W -
534803N 0011546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2626944444,53.8007361111,609.6 -1.2413818333,53.8096936667,609.6 -1.2527638889,53.8102666667,609.6 -1.2548809198,53.8122140415,609.6 -1.25688125,53.8142020278,609.6 -1.2714694444,53.8080694444,609.6 -1.2626944444,53.8007361111,609.6 + + + + +
+ + EGRU313C LEEDS EAST RWY 24 + 535208N 0010735W -
535142N 0010703W -
535117N 0010802W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 535004N 0011144W to
535143N 0010834W -
535208N 0010735W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1263416667,53.8689194444,609.6 -1.1427984167,53.8620370833,609.6 -1.1395753351,53.859719205,609.6 -1.1366436064,53.85726995300001,609.6 -1.1340184722,53.8547020833,609.6 -1.11755,53.8615888889,609.6 -1.1263416667,53.8689194444,609.6 + + + + +
+ + EGRU314A DONCASTER SHEFFIELD + A circle, 2.5 NM radius, centred at 532831N 0010015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0041361111,53.51688426390001,609.6 -1.0105763852,53.51670662890001,609.6 -1.0169615527,53.5161752438,609.6 -1.0232369828,53.51529465530001,609.6 -1.0293489916,53.5140723974,609.6 -1.0352453051,53.5125189269,609.6 -1.0408755098,53.5106475327,609.6 -1.0461914861,53.5084742213,609.6 -1.0511478222,53.5060175791,609.6 -1.0557022029,53.5032986123,609.6 -1.0598157723,53.5003405657,609.6 -1.0634534648,53.4971687231,609.6 -1.0665843034,53.49381018999999,609.6 -1.0691816618,53.4902936605,609.6 -1.0712234889,53.4866491717,609.6 -1.0726924933,53.48290784560001,609.6 -1.0735762858,53.479101623,609.6 -1.073867481,53.47526299010001,609.6 -1.0735637544,53.4714247011,609.6 -1.0726678572,53.4676194985,609.6 -1.0711875872,53.46387983370001,609.6 -1.0691357169,53.460237591,609.6 -1.0665298799,53.456723816,609.6 -1.0633924162,53.4533684518,609.6 -1.0597501774,53.4502000847,609.6 -1.0556342954,53.4472457018,609.6 -1.0510799147,53.4445304622,609.6 -1.0461258912,53.4420774838,609.6 -1.0408144611,53.4399076479,609.6 -1.0351908816,53.4380394225,609.6 -1.0293030466,53.4364887065,609.6 -1.023201081,53.4352686948,609.6 -1.0169369166,53.4343897676,609.6 -1.0105638537,53.4338594025,609.6 -1.0041361111,53.4336821114,609.6 -0.9977083685,53.4338594025,609.6 -0.9913353056000002,53.4343897676,609.6 -0.9850711413,53.4352686948,609.6 -0.9789691755999999,53.4364887065,609.6 -0.9730813406,53.4380394225,609.6 -0.9674577611,53.4399076479,609.6 -0.9621463311000001,53.4420774838,609.6 -0.9571923075,53.4445304622,609.6 -0.9526379268,53.4472457018,609.6 -0.9485220448,53.4502000847,609.6 -0.9448798061,53.4533684518,609.6 -0.9417423423,53.456723816,609.6 -0.9391365054,53.460237591,609.6 -0.9370846351000001,53.46387983370001,609.6 -0.935604365,53.4676194985,609.6 -0.9347084678000002,53.4714247011,609.6 -0.9344047412999998,53.47526299010001,609.6 -0.9346959364000001,53.479101623,609.6 -0.935579729,53.48290784560001,609.6 -0.9370487333,53.4866491717,609.6 -0.9390905604000001,53.4902936605,609.6 -0.9416879189,53.49381018999999,609.6 -0.9448187574,53.4971687231,609.6 -0.9484564499000001,53.5003405657,609.6 -0.9525700193,53.5032986123,609.6 -0.9571244001,53.5060175791,609.6 -0.9620807361,53.5084742213,609.6 -0.9673967124,53.5106475327,609.6 -0.9730269171,53.5125189269,609.6 -0.9789232306000001,53.5140723974,609.6 -0.9850352394,53.51529465530001,609.6 -0.9913106695000001,53.5161752438,609.6 -0.997695837,53.51670662890001,609.6 -1.0041361111,53.51688426390001,609.6 + + + + +
+ + EGRU314B DONCASTER SHEFFIELD RWY 02 + 532512N 0010132W -
532522N 0010224W -
532614N 0010156W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to
532604N 0010105W -
532512N 0010132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0256888889,53.4200222222,609.6 -1.0179736389,53.43451025,609.6 -1.0228580729,53.4352110427,609.6 -1.0276454322,53.4361200141,609.6 -1.0323108889,53.4372324444,609.6 -1.0400194444,53.4227472222,609.6 -1.0256888889,53.4200222222,609.6 + + + + +
+ + EGRU314C DONCASTER SHEFFIELD RWY 20 + 533150N 0005857W -
533140N 0005805W -
533048N 0005833W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 532831N 0010015W to
533058N 0005925W -
533150N 0005857W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.982525,53.5305361111,609.6 -0.9902676110999999,53.516054,609.6 -0.9853739193,53.51535160020001,609.6 -0.9805780853,53.51444061570001,609.6 -0.9759051111,53.51332580559999,609.6 -0.9681555556,53.5278111111,609.6 -0.982525,53.5305361111,609.6 + + + + +
+ + EGRU315A RETFORD/GAMSTON + A circle, 2 NM radius, centred at 531650N 0005705W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9513888889,53.31383741539999,609.6 -0.9571030807000002,53.3136608811,609.6 -0.9627565605,53.3131331538,609.6 -0.9682892657999999,53.3122598403,609.6 -0.9736424259999999,53.3110502186,609.6 -0.9787591905,53.3095171386,609.6 -0.9835852359999999,53.30767688499999,609.6 -0.9880693455,53.3055490027,609.6 -0.9921639543,53.30315608870001,609.6 -0.995825655,53.3005235503,609.6 -0.9990156584,53.29767933420001,609.6 -1.0017002027,53.2946536287,609.6 -1.0038509099,53.2914785415,609.6 -1.0054450831,53.2881877587,609.6 -1.0064659423,53.2848161856,609.6 -1.0069027981,53.2813995765,609.6 -1.0067511584,53.2779741546,609.6 -1.0060127711,53.2745762281,609.6 -1.0046955992,53.2712418052,609.6 -1.0028137304,53.2680062126,609.6 -1.000387223,53.2649037226,609.6 -0.9974418883,53.26196719019999,609.6 -0.9940090133,53.25922770649999,609.6 -0.9901250263,53.2567142704,609.6 -0.9858311092000001,53.2544534835,609.6 -0.9811727603,53.2524692693,609.6 -0.9761993128999999,53.2507826214,609.6 -0.9709634145000001,53.2494113829,609.6 -0.9655204716,53.2483700589,609.6 -0.9599280663,53.2476696632,609.6 -0.9542453511,53.2473176037,609.6 -0.9485324267,53.2473176037,609.6 -0.9428497114000001,53.2476696632,609.6 -0.9372573062,53.2483700589,609.6 -0.9318143633000001,53.2494113829,609.6 -0.9265784649,53.2507826214,609.6 -0.9216050175000001,53.2524692693,609.6 -0.9169466686,53.2544534835,609.6 -0.9126527514,53.2567142704,609.6 -0.9087687645,53.25922770649999,609.6 -0.9053358894999999,53.26196719019999,609.6 -0.9023905548000001,53.2649037226,609.6 -0.8999640474000001,53.2680062126,609.6 -0.8980821785999999,53.2712418052,609.6 -0.8967650065999999,53.2745762281,609.6 -0.8960266193999999,53.2779741546,609.6 -0.8958749796999999,53.2813995765,609.6 -0.8963118354,53.2848161856,609.6 -0.8973326947,53.2881877587,609.6 -0.8989268679,53.2914785415,609.6 -0.9010775751,53.2946536287,609.6 -0.9037621193999998,53.29767933420001,609.6 -0.9069521226999999,53.3005235503,609.6 -0.9106138235,53.30315608870001,609.6 -0.9147084323,53.3055490027,609.6 -0.9191925418,53.30767688499999,609.6 -0.9240185872,53.3095171386,609.6 -0.9291353516999998,53.3110502186,609.6 -0.9344885119,53.3122598403,609.6 -0.9400212173,53.3131331538,609.6 -0.9456746971000001,53.3136608811,609.6 -0.9513888889,53.31383741539999,609.6 + + + + +
+ + EGRU315B RETFORD/GAMSTON RWY 03 + 531359N 0005848W -
531413N 0005937W -
531509N 0005853W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to
531456N 0005804W -
531359N 0005848W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9799194443999999,53.2331333333,609.6 -0.9678115,53.2487633611,609.6 -0.9725227589,53.24977988360001,609.6 -0.9770623369,53.251046784,609.6 -0.9813933333,53.2525537778,609.6 -0.9934972222,53.23692222220001,609.6 -0.9799194443999999,53.2331333333,609.6 + + + + +
+ + EGRU315C RETFORD/GAMSTON RWY 21 + 531941N 0005522W -
531928N 0005433W -
531831N 0005517W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531650N 0005705W to
531844N 0005606W -
531941N 0005522W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9227055556,53.3281666667,609.6 -0.9349966667,53.31235547219999,609.6 -0.9302773589,53.3113403148,609.6 -0.9257303104,53.3100743476,609.6 -0.9213926111,53.30856788889999,609.6 -0.9090972222,53.3243777778,609.6 -0.9227055556,53.3281666667,609.6 + + + + +
+ + EGRU316A SYERSTON + A circle, 2 NM radius, centred at 530124N 0005442W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9116666667,53.0566166392,609.6 -0.9173467706999999,53.0564400985,609.6 -0.9229665261999999,53.055912352,609.6 -0.9284662301999999,53.0550390067,609.6 -0.9337874638,53.0538293406,609.6 -0.9388737164000001,53.0522962039,609.6 -0.9436709894,53.0504558815,609.6 -0.9481283717999999,53.0483279189,609.6 -0.9521985826,53.0459349133,609.6 -0.9558384733,53.0433022727,609.6 -0.9590094850000001,53.04045794449999,609.6 -0.961678057,53.03743211769999,609.6 -0.9638159791000001,53.03425690120001,609.6 -0.9654006883,53.030965982,609.6 -0.9664155033,53.0275942667,609.6 -0.9668497966,53.0241775111,609.6 -0.9666991014000001,53.0207519397,609.6 -0.9659651533,53.01735386240001,609.6 -0.9646558661,53.014019289,609.6 -0.9627852421999998,53.0107835481,609.6 -0.9603732189,53.0076809138,609.6 -0.9574454526,53.00474424280001,609.6 -0.9540330431000001,53.0020046282,609.6 -0.9501722013,52.9994910706,609.6 -0.9459038633,52.9972301731,609.6 -0.9412732567999998,52.995245861,609.6 -0.9363294217,52.99355912920001,609.6 -0.9311246926000001,52.9921878221,609.6 -0.9257141471,52.9911464456,609.6 -0.9201550256,52.9904460146,609.6 -0.9145061296,52.9900939372,609.6 -0.9088272037,52.9900939372,609.6 -0.9031783076999998,52.9904460146,609.6 -0.8976191863,52.9911464456,609.6 -0.8922086407000001,52.9921878221,609.6 -0.8870039117000001,52.99355912920001,609.6 -0.8820600765,52.995245861,609.6 -0.8774294700000002,52.9972301731,609.6 -0.873161132,52.9994910706,609.6 -0.8693002902,53.0020046282,609.6 -0.8658878807000001,53.00474424280001,609.6 -0.8629601145,53.0076809138,609.6 -0.8605480911,53.0107835481,609.6 -0.8586774672,53.014019289,609.6 -0.85736818,53.01735386240001,609.6 -0.8566342319,53.0207519397,609.6 -0.8564835367,53.0241775111,609.6 -0.85691783,53.0275942667,609.6 -0.8579326451,53.030965982,609.6 -0.8595173543,53.03425690120001,609.6 -0.8616552763999998,53.03743211769999,609.6 -0.8643238483,53.04045794449999,609.6 -0.8674948600999999,53.0433022727,609.6 -0.8711347507,53.0459349133,609.6 -0.8752049614999999,53.0483279189,609.6 -0.8796623439,53.0504558815,609.6 -0.8844596169000001,53.0522962039,609.6 -0.8895458695000001,53.0538293406,609.6 -0.8948671030999999,53.0550390067,609.6 -0.9003668070999999,53.055912352,609.6 -0.9059865625999999,53.0564400985,609.6 -0.9116666667,53.0566166392,609.6 + + + + +
+ + EGRU316B SYERSTON RWY 02L + 525833N 0005647W -
525847N 0005735W -
525949N 0005644W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525933N 0005557W -
525833N 0005647W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9462611111,52.97575277779999,609.6 -0.9326351667,52.9925465278,609.6 -0.9371605542,52.99381488500001,609.6 -0.9414777553,52.9953246472,609.6 -0.9455515000000001,52.9970634722,609.6 -0.9596277778000001,52.9797083333,609.6 -0.9462611111,52.97575277779999,609.6 + + + + +
+ + EGRU316C SYERSTON RWY 20R + 530411N 0005312W -
530356N 0005223W -
530308N 0005303W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530320N 0005353W -
530411N 0005312W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8865611111,53.06962499999999,609.6 -0.8979961667000002,53.0555806111,609.6 -0.8932158648,53.0547037456,609.6 -0.8885868653,53.0535700163,609.6 -0.8841471111,53.0521887222,609.6 -0.8731666667,53.0656694444,609.6 -0.8865611111,53.06962499999999,609.6 + + + + +
+ + EGRU316D SYERSTON RWY 02R + 525834N 0005641W -
525848N 0005729W -
525948N 0005640W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525932N 0005553W -
525834N 0005641W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9445833333,52.9761,609.6 -0.9314683889000001,52.99226672219999,609.6 -0.9360344625999999,52.9934709154,609.6 -0.9404020882,52.9949186579,609.6 -0.9445356667000001,52.9965981667,609.6 -0.9579527778,52.9800527778,609.6 -0.9445833333,52.9761,609.6 + + + + +
+ + EGRU316E SYERSTON RWY 20L + 530411N 0005306W -
530357N 0005218W -
530307N 0005259W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530319N 0005348W -
530411N 0005306W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8850333333,53.0698027778,609.6 -0.8967719444,53.0553830278,609.6 -0.8920324996,53.0544416819,609.6 -0.8874536336000001,53.05324629319999,609.6 -0.8830727778,53.0518066389,609.6 -0.8716361110999999,53.06584999999999,609.6 -0.8850333333,53.0698027778,609.6 + + + + +
+ + EGRU316F SYERSTON RWY 06 + 525941N 0005911W -
530010N 0005936W -
530043N 0005749W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530015N 0005724W -
525941N 0005911W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9864583333,52.99472777779999,609.6 -0.9567000000000001,53.0040936667,609.6 -0.9593936936,53.0066201301,609.6 -0.9616990915,53.0092827496,609.6 -0.9635973611,53.0120598611,609.6 -0.9933361111,53.0027,609.6 -0.9864583333,52.99472777779999,609.6 + + + + +
+ + EGRU316G SYERSTON RWY 24 + 530305N 0005018W -
530236N 0004953W -
530204N 0005135W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530233N 0005200W -
530305N 0005018W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8383527777999999,53.0513527778,609.6 -0.8665545278,53.0425228056,609.6 -0.8638693661999999,53.0399925578,609.6 -0.8615739082,53.03732666330001,609.6 -0.8596867778,53.0345468611,609.6 -0.8314638889,53.0433833333,609.6 -0.8383527777999999,53.0513527778,609.6 + + + + +
+ + EGRU316H SYERSTON RWY 06L + 525945N 0005907W -
530013N 0005931W -
530045N 0005750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530016N 0005726W -
525945N 0005907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9851694444,52.99570000000001,609.6 -0.9571801944,53.0045089444,609.6 -0.959810169,53.00706010329999,609.6 -0.9620483698,53.00974386450001,609.6 -0.9638765,53.0125383889,609.6 -0.9920472222,53.0036722222,609.6 -0.9851694444,52.99570000000001,609.6 + + + + +
+ + EGRU316I SYERSTON RWY 24R + 530301N 0005038W -
530232N 0005013W -
530206N 0005136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530235N 0005201W -
530301N 0005038W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8438194444,53.0502083333,609.6 -0.8670451944000002,53.0429354444,609.6 -0.8642959963000001,53.0404299106,609.6 -0.8619331102,53.0377851374,609.6 -0.8599757221999998,53.0350226944,609.6 -0.8369305556,53.0422388889,609.6 -0.8438194444,53.0502083333,609.6 + + + + +
+ + EGRU316J SYERSTON RWY 06R + 525942N 0005904W -
530010N 0005929W -
530042N 0005748W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530014N 0005723W -
525942N 0005904W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9844611111,52.9948861111,609.6 -0.9562944167,53.0037530833,609.6 -0.9590402789,53.0062585353,609.6 -0.961400833,53.00890304819999,609.6 -0.9633568056,53.0116651111,609.6 -0.9913388889,53.0028555556,609.6 -0.9844611111,52.9948861111,609.6 + + + + +
+ + EGRU316K SYERSTON RWY 24L + 530256N 0005042W -
530227N 0005017W -
530203N 0005134W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530232N 0005158W -
530256N 0005042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8450555555999999,53.0487972222,609.6 -0.8661643610999999,53.0421849444,609.6 -0.8635312747,53.03963472920001,609.6 -0.8612906516,53.0369517821,609.6 -0.8594606943999998,53.03415797219999,609.6 -0.8381666667,53.0408277778,609.6 -0.8450555555999999,53.0487972222,609.6 + + + + +
+ + EGRU316L SYERSTON RWY 11 + 530158N 0005936W -
530229N 0005919W -
530210N 0005745W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530139N 0005759W -
530158N 0005936W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9932277778,53.0327916667,609.6 -0.9664401111000001,53.0274773611,609.6 -0.9655974503999999,53.0304427487,609.6 -0.9643139209,53.0333501353,609.6 -0.9625999167,53.03617575,609.6 -0.9885555556,53.041325,609.6 -0.9932277778,53.0327916667,609.6 + + + + +
+ + EGRU316M SYERSTON RWY 29 + 530042N 0005021W -
530011N 0005038W -
530025N 0005149W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530055N 0005129W -
530042N 0005021W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8391277778,53.01158611109999,609.6 -0.8580746667,53.0153695556,609.6 -0.8594877637,53.0124841721,609.6 -0.8613268855,53.0096875054,609.6 -0.8635769444,53.0070023889,609.6 -0.8437972222,53.0030527778,609.6 -0.8391277778,53.01158611109999,609.6 + + + + +
+ + EGRU316N SYERSTON RWY 11L + 530201N 0005937W -
530231N 0005921W -
530212N 0005744W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530141N 0005759W -
530201N 0005937W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9937388889,53.0334777778,609.6 -0.9663150833000002,53.0280407778,609.6 -0.965389513,53.0309945302,609.6 -0.9640255096,53.0338858783,609.6 -0.9622341110999999,53.0366912222,609.6 -0.9890666666999999,53.04201111110001,609.6 -0.9937388889,53.0334777778,609.6 + + + + +
+ + EGRU316O SYERSTON RWY 29R + 530038N 0004954W -
530008N 0005010W -
530027N 0005147W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530057N 0005128W -
530038N 0004954W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8315305556,53.0106722222,609.6 -0.8578550556,53.01592669439999,609.6 -0.8591842718,53.0130296541,609.6 -0.8609412356999999,53.0102167252,609.6 -0.8631115556,53.00751083330001,609.6 -0.8361972222,53.00213888889999,609.6 -0.8315305556,53.0106722222,609.6 + + + + +
+ + EGRU316P SYERSTON RWY 11R + 530157N 0005940W -
530228N 0005923W -
530209N 0005747W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530137N 0005800W -
530157N 0005940W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9944416667,53.03249722220001,609.6 -0.9665396667,53.0269653611,609.6 -0.9657723513000001,53.029941211,609.6 -0.9645618371,53.0328630501,609.6 -0.9629179722,53.0357069444,609.6 -0.9897694444,53.0410305556,609.6 -0.9944416667,53.03249722220001,609.6 + + + + +
+ + EGRU316Q SYERSTON RWY 29L + 530034N 0004949W -
530003N 0005006W -
530024N 0005150W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530054N 0005130W -
530034N 0004949W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8303138889,53.00930833330001,609.6 -0.8582771389,53.01489019440001,609.6 -0.8597627878,53.0120150787,609.6 -0.8616730086,53.0092326862,609.6 -0.8639921111,53.0065657778,609.6 -0.8349805556,53.000775,609.6 -0.8303138889,53.00930833330001,609.6 + + + + +
+ + EGRU316R SYERSTON RWY 15 + 530357N 0005715W -
530413N 0005628W -
530319N 0005538W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530306N 0005627W -
530357N 0005715W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9541083332999999,53.0658666667,609.6 -0.9407998056,53.05160730560001,609.6 -0.9364328997,53.0530812795,609.6 -0.9318622098,53.05431083599999,609.6 -0.9271253333,53.0552858611,609.6 -0.9411000000000002,53.0702638889,609.6 -0.9541083332999999,53.0658666667,609.6 + + + + +
+ + EGRU316S SYERSTON RWY 33 + 525859N 0005135W -
525843N 0005222W -
525937N 0005312W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525955N 0005228W -
525859N 0005135W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8598138889,52.9829722222,609.6 -0.8744734444,52.9987451111,609.6 -0.8783162842,52.99681589679999,609.6 -0.8824324816,52.995104339,609.6 -0.8867882778,52.9936244722,609.6 -0.8727944444,52.9785722222,609.6 -0.8598138889,52.9829722222,609.6 + + + + +
+ + EGRU316T SYERSTON RWY 15L + 530354N 0005709W -
530410N 0005622W -
530320N 0005534W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530307N 0005624W -
530354N 0005709W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9523777778,53.06511111109999,609.6 -0.9400369167,53.0518878056,609.6 -0.935623392,53.0533211891,609.6 -0.9310120734,53.05450734839999,609.6 -0.9262410277999999,53.0554365,609.6 -0.9393694444,53.0695083333,609.6 -0.9523777778,53.06511111109999,609.6 + + + + +
+ + EGRU316U SYERSTON RWY 33R + 525857N 0005130W -
525841N 0005217W -
525938N 0005310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525957N 0005226W -
525857N 0005130W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8583611111,52.9825083333,609.6 -0.8738008056,52.9991213611,609.6 -0.8775965703,52.99715075990001,609.6 -0.8816725552999999,52.99539580370001,609.6 -0.8859951944,52.99387091669999,609.6 -0.8713416667000001,52.9781083333,609.6 -0.8583611111,52.9825083333,609.6 + + + + +
+ + EGRU316V SYERSTON RWY 15R + 530355N 0005717W -
530411N 0005630W -
530318N 0005541W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
530305N 0005630W -
530355N 0005717W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9546638889,53.0653361111,609.6 -0.94156925,53.0513138889,609.6 -0.9372483332,53.0528294872,609.6 -0.9327174011,53.0541032867,609.6 -0.9280136389,53.0551248333,609.6 -0.9416555556,53.0697388889,609.6 -0.9546638889,53.0653361111,609.6 + + + + +
+ + EGRU316W SYERSTON RWY 33L + 525901N 0005141W -
525845N 0005228W -
525936N 0005315W thence anti-clockwise by the arc of a circle radius 2 NM centred on 530124N 0005442W to
525954N 0005231W -
525901N 0005141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8614138889,52.9836138889,609.6 -0.8751460277999998,52.9983811389,609.6 -0.8790351997000001,52.9964925478,609.6 -0.8831911022,52.9948236641,609.6 -0.88757975,52.99338813890001,609.6 -0.8743916667000001,52.97921111109999,609.6 -0.8614138889,52.9836138889,609.6 + + + + +
+ + EGRU317A SANDTOFT + A circle, 2 NM radius, centred at 533335N 0005130W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8583333332999999,53.5930025171,609.6 -0.8640851205,53.5928259897,609.6 -0.8697757947,53.5922982831,609.6 -0.8753448971,53.5914250039,609.6 -0.880733269,53.5902154301,609.6 -0.8858836849,53.58868241129999,609.6 -0.8907414632999999,53.58684223189999,609.6 -0.8952550498,53.5847144365,609.6 -0.8993765668,53.5823216214,609.6 -0.9030623216,53.5796891934,609.6 -0.9062732702000001,53.57684509849999,609.6 -0.9089754301000001,53.5738195239,609.6 -0.9111402375999998,53.5706445766,609.6 -0.9127448481,53.5673539412,609.6 -0.913772373,53.5639825219,609.6 -0.9142120543999999,53.5605660714,609.6 -0.9140593726999999,53.5571408114,609.6 -0.9133160892,53.5537430482,609.6 -0.9119902209,53.5504087882,609.6 -0.91009595,53.5471733563,609.6 -0.907653468,53.5440710226,609.6 -0.9046887571,53.5411346403,609.6 -0.9012333109,53.5383952985,609.6 -0.8973237974000001,53.5358819942,609.6 -0.8930016694,53.53362132709999,609.6 -0.8883127239,53.531637219,609.6 -0.8833066178,53.5299506621,609.6 -0.8780363436000002,53.5285794981,609.6 -0.8725576704000001,53.52753823089999,609.6 -0.8669285573,53.5268378737,609.6 -0.8612085435,53.5264858335,609.6 -0.8554581230999999,53.5264858335,609.6 -0.8497381094000001,53.5268378737,609.6 -0.8441089963,53.52753823089999,609.6 -0.8386303231,53.5285794981,609.6 -0.8333600489,53.5299506621,609.6 -0.8283539428,53.531637219,609.6 -0.8236649971999999,53.53362132709999,609.6 -0.8193428692,53.5358819942,609.6 -0.8154333557999999,53.5383952985,609.6 -0.8119779095,53.5411346403,609.6 -0.8090131986999999,53.5440710226,609.6 -0.8065707167,53.5471733563,609.6 -0.8046764457999999,53.5504087882,609.6 -0.8033505775000001,53.5537430482,609.6 -0.802607294,53.5571408114,609.6 -0.8024546123,53.5605660714,609.6 -0.8028942936,53.5639825219,609.6 -0.8039218185999999,53.5673539412,609.6 -0.805526429,53.5706445766,609.6 -0.8076912366,53.5738195239,609.6 -0.8103933964,53.57684509849999,609.6 -0.8136043451,53.5796891934,609.6 -0.8172900999,53.5823216214,609.6 -0.8214116167999999,53.5847144365,609.6 -0.8259252034,53.58684223189999,609.6 -0.8307829817000001,53.58868241129999,609.6 -0.8359333976,53.5902154301,609.6 -0.8413217696,53.5914250039,609.6 -0.8468908719000001,53.5922982831,609.6 -0.8525815462,53.5928259897,609.6 -0.8583333332999999,53.5930025171,609.6 + + + + +
+ + EGRU317B SANDTOFT RWY 05 + 533118N 0005438W -
533141N 0005517W -
533222N 0005409W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to
533159N 0005330W -
533118N 0005438W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.91055,53.5216333333,609.6 -0.8917588611,53.5330525556,609.6 -0.8956587241,53.5349549572,609.6 -0.8992552579999998,53.537058912,609.6 -0.9025191667,53.5393473333,609.6 -0.9213083332999998,53.5279277778,609.6 -0.91055,53.5216333333,609.6 + + + + +
+ + EGRU317C SANDTOFT RWY 23 + 533547N 0004830W -
533525N 0004751W -
533448N 0004851W thence anti-clockwise by the arc of a circle radius 2 NM centred on 533335N 0005130W to
533511N 0004930W -
533547N 0004830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8082888888999999,53.5964805556,609.6 -0.8249266389,53.5864094444,609.6 -0.8210211529000001,53.58450809960001,609.6 -0.8174199323999999,53.5824049166,609.6 -0.8141522778,53.5801170556,609.6 -0.7975111110999999,53.5901888889,609.6 -0.8082888888999999,53.5964805556,609.6 + + + + +
+ + EGRU319A WADDINGTON + A circle, 2.5 NM radius, centred at 530958N 0003126W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5238888889,53.2077142103,609.6 -0.5302827139,53.207536568,609.6 -0.5366218315,53.207005161,609.6 -0.5428520067,53.2061245359,609.6 -0.5489199443,53.204902227,609.6 -0.5547737485999999,53.2033486911,609.6 -0.5603633708,53.20147721719999,609.6 -0.5656410391,53.19930381209999,609.6 -0.5705616695,53.1968470626,609.6 -0.5750832522,53.194127975,609.6 -0.5791672108,53.19116979489999,609.6 -0.582778732,53.1879978065,609.6 -0.5858870608,53.1846391161,609.6 -0.5884657617,53.1811224189,609.6 -0.5904929406,53.1774777527,609.6 -0.5919514285,53.1737362408,609.6 -0.5928289237,53.1699298254,609.6 -0.5931180914,53.16609099429999,609.6 -0.5928166217,53.1622525033,609.6 -0.5919272434,53.1584470964,609.6 -0.5904576959,53.15470722720001,609.6 -0.5884206578,53.1510647819,609.6 -0.5858336336,53.14755080820001,609.6 -0.5827188008,53.1441952511,609.6 -0.5791028166,53.1410266992,609.6 -0.5750165877,53.1380721416,609.6 -0.5704950051,53.13535673929999,609.6 -0.5655766448,53.1329036124,609.6 -0.5603034396,53.1307336437,609.6 -0.5547203213,53.12886530310001,609.6 -0.5488748403,53.12731449070001,609.6 -0.542816762,53.1260944027,609.6 -0.5365976464,53.1252154203,609.6 -0.5302704118,53.1246850218,609.6 -0.5238888889,53.12450771950001,609.6 -0.517507366,53.1246850218,609.6 -0.5111801314,53.1252154203,609.6 -0.5049610157,53.1260944027,609.6 -0.4989029375,53.12731449070001,609.6 -0.4930574565,53.12886530310001,609.6 -0.4874743382000001,53.1307336437,609.6 -0.4822011329,53.1329036124,609.6 -0.4772827727,53.13535673929999,609.6 -0.4727611901,53.1380721416,609.6 -0.4686749612,53.1410266992,609.6 -0.465058977,53.1441952511,609.6 -0.4619441442,53.14755080820001,609.6 -0.4593571200000001,53.1510647819,609.6 -0.4573200818,53.15470722720001,609.6 -0.4558505344000001,53.1584470964,609.6 -0.4549611561,53.1622525033,609.6 -0.4546596863,53.16609099429999,609.6 -0.4549488541,53.1699298254,609.6 -0.4558263492,53.1737362408,609.6 -0.4572848372,53.1774777527,609.6 -0.4593120161,53.1811224189,609.6 -0.4618907169000001,53.1846391161,609.6 -0.4649990458000001,53.1879978065,609.6 -0.4686105669999999,53.19116979489999,609.6 -0.4726945256000001,53.194127975,609.6 -0.4772161083000001,53.1968470626,609.6 -0.4821367386,53.19930381209999,609.6 -0.487414407,53.20147721719999,609.6 -0.4930040291,53.2033486911,609.6 -0.4988578335000001,53.204902227,609.6 -0.504925771,53.2061245359,609.6 -0.5111559462,53.207005161,609.6 -0.5174950639,53.207536568,609.6 -0.5238888889,53.2077142103,609.6 + + + + +
+ + EGRU319B WADDINGTON RWY 02 + 530639N 0003308W -
530651N 0003358W -
530746N 0003322W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to
530734N 0003233W -
530639N 0003308W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5523125556,53.11095211109999,609.6 -0.54236325,53.12601786110001,609.6 -0.5471194495,53.1269222092,609.6 -0.5517551548,53.1280302058,609.6 -0.5562463056,53.1293361111,609.6 -0.5661892777999999,53.1142725833,609.6 -0.5523125556,53.11095211109999,609.6 + + + + +
+ + EGRU319C WADDINGTON RWY 20 + 531313N 0002946W -
531301N 0002856W -
531210N 0002929W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530958N 0003126W to
531222N 0003019W -
531313N 0002946W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4960258889,53.2203266667,609.6 -0.5053914167,53.2062031111,609.6 -0.5006270692,53.2052975907,609.6 -0.4959840364000001,53.2041880917,609.6 -0.4914865278,53.2028803889,609.6 -0.4821149167,53.21700625,609.6 -0.4960258889,53.2203266667,609.6 + + + + +
+ + EGRU320A CRANWELL + A circle, 2.5 NM radius, centred at 530147N 0002934W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4927527778,53.07133739139999,609.6 -0.4991263854,53.0711597458,609.6 -0.5054454595,53.070628329,609.6 -0.5116559371,53.06974768780001,609.6 -0.5177046922,53.0685253563,609.6 -0.523539994,53.06697179129999,609.6 -0.5291119522,53.0651002821,609.6 -0.5343729466,53.06292683549999,609.6 -0.5392780356,53.0604700383,609.6 -0.5437853424,53.0577508973,609.6 -0.5478564126,53.05479265799999,609.6 -0.5514565422,53.0516206051,609.6 -0.5545550733,53.0482618451,609.6 -0.5571256530000001,53.04474507350001,609.6 -0.5591464559,53.0411003288,609.6 -0.5606003663,53.0373587348,609.6 -0.5614751202,53.03355223420001,609.6 -0.5617634053,53.0297133154,609.6 -0.5614629176,53.025874735,609.6 -0.5605763766,53.0220692379,609.6 -0.559111496,53.0183292784,609.6 -0.5570809135,53.0146867436,609.6 -0.5545020777,53.011172682,609.6 -0.5513970952,53.0078170398,609.6 -0.5477925386,53.0046484063,609.6 -0.5437192166,53.00169377149999,609.6 -0.5392119097,52.9989782975,609.6 -0.5343090725,52.99652510500001,609.6 -0.5290525052,52.9943550778,609.6 -0.5234869983,52.9924866863,609.6 -0.5176599526,52.9909358313,609.6 -0.5116209771,52.98971570970001,609.6 -0.5054214697,52.988836703,609.6 -0.4991141827,52.98830628979999,609.6 -0.4927527778,52.9881289825,609.6 -0.4863913728,52.98830628979999,609.6 -0.4800840859,52.988836703,609.6 -0.4738845785,52.98971570970001,609.6 -0.467845603,52.9909358313,609.6 -0.4620185572,52.9924866863,609.6 -0.4564530503999999,52.9943550778,609.6 -0.4511964831,52.99652510500001,609.6 -0.4462936458,52.9989782975,609.6 -0.441786339,53.00169377149999,609.6 -0.437713017,53.0046484063,609.6 -0.4341084603,53.0078170398,609.6 -0.4310034778,53.011172682,609.6 -0.428424642,53.0146867436,609.6 -0.4263940595,53.0183292784,609.6 -0.424929179,53.0220692379,609.6 -0.424042638,53.025874735,609.6 -0.4237421503,53.0297133154,609.6 -0.4240304353,53.03355223420001,609.6 -0.4249051893,53.0373587348,609.6 -0.4263590997,53.0411003288,609.6 -0.4283799025,53.04474507350001,609.6 -0.4309504822,53.0482618451,609.6 -0.4340490133,53.0516206051,609.6 -0.437649143,53.05479265799999,609.6 -0.4417202131,53.0577508973,609.6 -0.4462275199,53.0604700383,609.6 -0.451132609,53.06292683549999,609.6 -0.4563936033,53.0651002821,609.6 -0.4619655615,53.06697179129999,609.6 -0.4678008634,53.0685253563,609.6 -0.4738496185,53.06974768780001,609.6 -0.4800600961,53.070628329,609.6 -0.4863791702,53.0711597458,609.6 -0.4927527778,53.07133739139999,609.6 + + + + +
+ + EGRU320B CRANWELL RWY 01 + 525833N 0002919W -
525838N 0003012W -
525918N 0003003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
525918N 0002909W -
525833N 0002919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4886638889,52.9759416667,609.6 -0.4857053333,52.9883466944,609.6 -0.4907135656,52.9881471692,609.6 -0.4957325729,52.9881678233,609.6 -0.5007358333,52.9884085556,609.6 -0.5034,52.97722222220001,609.6 -0.4886638889,52.9759416667,609.6 + + + + +
+ + EGRU320C CRANWELL RWY 19 + 530445N 0002845W -
530440N 0002751W -
530406N 0002800W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530415N 0002852W -
530445N 0002845W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4790694444,53.0791638889,609.6 -0.4810846389,53.0707389722,609.6 -0.4761629955,53.0701185314,609.6 -0.4713295119,53.0692838807,609.6 -0.4666098611,53.0682394722,609.6 -0.4643,53.0778833333,609.6 -0.4790694444,53.0791638889,609.6 + + + + +
+ + EGRU320D CRANWELL RWY 08 + 530107N 0003443W -
530139N 0003450W -
530144N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530112N 0003335W -
530107N 0003443W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5786777778,53.01853333330001,609.6 -0.559841,53.02000063890001,609.6 -0.5608322153999999,53.0229411873,609.6 -0.5614694696,53.0259171598,609.6 -0.5617493611,53.0289130833,609.6 -0.5805666667,53.0274472222,609.6 -0.5786777778,53.01853333330001,609.6 + + + + +
+ + EGRU320E CRANWELL RWY 26 + 530227N 0002421W -
530155N 0002414W -
530150N 0002526W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530222N 0002532W -
530227N 0002421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4057472221999999,53.0409472222,609.6 -0.4256331389,53.0394249444,609.6 -0.4246510811999999,53.0364830877,609.6 -0.4240234783999999,53.0335062108,609.6 -0.4237535278,53.03050980559999,609.6 -0.40385,53.0320333333,609.6 -0.4057472221999999,53.0409472222,609.6 + + + + +
+ + EGRU320F CRANWELL RWY 08N + 530107N 0003416W -
530139N 0003423W -
530142N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530110N 0003335W -
530107N 0003416W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5711777778,53.01854999999999,609.6 -0.55959675,53.01940886109999,609.6 -0.560659422,53.022340648,609.6 -0.5613689532,53.02531099199999,609.6 -0.5617215833,53.02830444439999,609.6 -0.5729805556000001,53.0274694444,609.6 -0.5711777778,53.01854999999999,609.6 + + + + +
+ + EGRU320G CRANWELL RWY 26N + 530221N 0002450W -
530149N 0002443W -
530146N 0002525W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530218N 0002531W -
530221N 0002450W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4137722222,53.039175,609.6 -0.4252282222,53.0383400278,609.6 -0.4243769460999999,53.0353831851,609.6 -0.4238815851,53.0323970413,609.6 -0.4237446389000001,53.02939713889999,609.6 -0.4119666666999999,53.0302555556,609.6 -0.4137722222,53.039175,609.6 + + + + +
+ + EGRU320H CRANWELL RWY 06 + 530100N 0003352W -
530129N 0003415W -
530139N 0003342W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530106N 0003333W -
530100N 0003352W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5643539444,53.0167546667,609.6 -0.5590889999999999,53.0182818889,609.6 -0.56032936,53.0213150389,609.6 -0.5611889152,53.0243957527,609.6 -0.56166275,53.02750666670001,609.6 -0.5708006667,53.0248561111,609.6 -0.5643539444,53.0167546667,609.6 + + + + +
+ + EGRU320I CRANWELL RWY 24 + 530406N 0002513W -
530337N 0002450W -
530314N 0002611W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530339N 0002648W -
530406N 0002513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4202738333,53.0683875833,609.6 -0.4467458333,53.0607521667,609.6 -0.4430133857,53.0585835142,609.6 -0.439561951,53.05625214110001,609.6 -0.4364109722,53.0537712222,609.6 -0.4138206111,53.0602862222,609.6 -0.4202738333,53.0683875833,609.6 + + + + +
+ + EGRU320K CRANWELL RWY 21 + 530519N 0002721W -
530503N 0002635W -
530359N 0002737W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530147N 0002934W to
530411N 0002828W -
530519N 0002721W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4558644444,53.08874525,609.6 -0.4743584167,53.0698336944,609.6 -0.4695525918,53.0689181653,609.6 -0.4648706423,53.0677938034,609.6 -0.4603375555999999,53.06646661109999,609.6 -0.4430011389,53.0841885,609.6 -0.4558644444,53.08874525,609.6 + + + + +
+ + EGRU321A HUMBERSIDE + A circle, 2.5 NM radius, centred at 533424N 0002105W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3514583333,53.61503079920001,609.6 -0.3579135341,53.6148531665,609.6 -0.3643135,53.6143217883,609.6 -0.370603473,53.61344121129999,609.6 -0.3767296443,53.61221896959999,609.6 -0.3826396183,53.6106655197,609.6 -0.3882828644,53.6087941506,609.6 -0.3936111511,53.60662086890001,609.6 -0.3985789612,53.6041642607,609.6 -0.4031438816999999,53.601445332,609.6 -0.4072669666,53.5984873276,609.6 -0.4109130692,53.5953155311,609.6 -0.4140511412,53.5919570477,609.6 -0.4166544952,53.5884405714,609.6 -0.4187010295,53.58479613869999,609.6 -0.4201734131,53.58105487139999,609.6 -0.4210592292,53.5772487098,609.6 -0.4213510757,53.5734101397,609.6 -0.4210466237,53.5695719148,609.6 -0.4201486315,53.5657667769,609.6 -0.4186649156,53.56202717690001,609.6 -0.4166082789,53.5583849984,609.6 -0.4139963963,53.5548712864,609.6 -0.41085166,53.5515159834,609.6 -0.4072009842000001,53.54834767490001,609.6 -0.4030755731,53.54539334739999,609.6 -0.3985106526,53.5426781594,609.6 -0.3935451687,53.5402252281,609.6 -0.388221455,53.5380554343,609.6 -0.3825848733000001,53.5361872456,609.6 -0.3766834279,53.5346365601,609.6 -0.3705673591,53.5334165726,609.6 -0.3642887183,53.5325376629,609.6 -0.3579009286,53.5320073084,609.6 -0.3514583333,53.5318300209,609.6 -0.3450157381,53.5320073084,609.6 -0.3386279483,53.5325376629,609.6 -0.3323493076,53.5334165726,609.6 -0.3262332388,53.5346365601,609.6 -0.3203317933,53.5361872456,609.6 -0.3146952116,53.5380554343,609.6 -0.309371498,53.5402252281,609.6 -0.304406014,53.5426781594,609.6 -0.2998410935,53.54539334739999,609.6 -0.2957156825,53.54834767490001,609.6 -0.2920650067,53.5515159834,609.6 -0.2889202703,53.5548712864,609.6 -0.2863083878,53.5583849984,609.6 -0.284251751,53.56202717690001,609.6 -0.2827680351,53.5657667769,609.6 -0.2818700429,53.5695719148,609.6 -0.281565591,53.5734101397,609.6 -0.2818574375,53.5772487098,609.6 -0.2827432535,53.58105487139999,609.6 -0.2842156372,53.58479613869999,609.6 -0.2862621715,53.5884405714,609.6 -0.2888655254,53.5919570477,609.6 -0.2920035974,53.5953155311,609.6 -0.2956497001,53.5984873276,609.6 -0.299772785,53.601445332,609.6 -0.3043377054,53.6041642607,609.6 -0.3093055156,53.60662086890001,609.6 -0.3146338023,53.6087941506,609.6 -0.3202770483,53.6106655197,609.6 -0.3261870224,53.61221896959999,609.6 -0.3323131937,53.61344121129999,609.6 -0.3386031667,53.6143217883,609.6 -0.3450031326,53.6148531665,609.6 -0.3514583333,53.61503079920001,609.6 + + + + +
+ + EGRU321B HUMBERSIDE RWY 02 + 533119N 0002244W -
533132N 0002334W -
533213N 0002305W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533201N 0002215W -
533119N 0002244W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3787722222000001,53.5220722222,609.6 -0.3709044722,53.5334741944,609.6 -0.3756882022,53.5344122774,609.6 -0.380346243,53.53555314679999,609.6 -0.3848544167,53.5368908889,609.6 -0.3927166667,53.5254916667,609.6 -0.3787722222000001,53.5220722222,609.6 + + + + +
+ + EGRU321C HUMBERSIDE RWY 20 + 533729N 0001927W -
533717N 0001836W -
533636N 0001905W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533648N 0001955W -
533729N 0001927W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3240805556,53.6247805556,609.6 -0.33197675,53.6133836944,609.6 -0.3271853186,53.6124439859,609.6 -0.32252048,53.6113011963,609.6 -0.3180065556,53.6099612778,609.6 -0.3101027778,53.62136388889999,609.6 -0.3240805556,53.6247805556,609.6 + + + + +
+ + EGRU321D HUMBERSIDE RWY 08 + 533356N 0002538W -
533428N 0002545W -
533430N 0002517W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533358N 0002513W -
533356N 0002538W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4272916667,53.5654611111,609.6 -0.4202290833,53.5660261111,609.6 -0.420950153,53.5690011489,609.6 -0.4213085477,53.5719994114,609.6 -0.4213023055999999,53.57500525,609.6 -0.4292833333,53.57436666669999,609.6 -0.4272916667,53.5654611111,609.6 + + + + +
+ + EGRU321E HUMBERSIDE RWY 26 + 533513N 0001609W -
533441N 0001602W -
533437N 0001655W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 533424N 0002105W to
533509N 0001705W -
533513N 0001609W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2691388889,53.587075,609.6 -0.2847413611,53.5858466111,609.6 -0.2834108694,53.5829460348,609.6 -0.2824360879,53.5799958388,609.6 -0.2818220278,53.5770114444,609.6 -0.2671444444,53.5781666667,609.6 -0.2691388889,53.587075,609.6 + + + + +
+ + EGRU322A WICKENBY + A circle, 2 NM radius, centred at 531901N 0002056W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3487972222,53.3502177668,609.6 -0.3545162778,53.3500412334,609.6 -0.3601745694,53.3495135088,609.6 -0.3657119835,53.34864019969999,609.6 -0.371069699,53.3474305843,609.6 -0.376190817,53.34589751230001,609.6 -0.3810209678,53.3440572683,609.6 -0.3855088907999999,53.34192939739999,609.6 -0.3896069807,53.3395364964,609.6 -0.3932717934,53.3369039724,609.6 -0.3964645064000001,53.3340597721,609.6 -0.3991513297,53.3310340837,609.6 -0.4013038611,53.3278590148,609.6 -0.4028993846,53.3245682512,609.6 -0.4039211062,53.3211966981,609.6 -0.4043583274999999,53.3177801097,609.6 -0.4042065530999999,53.314354709,609.6 -0.4034675323999999,53.3109568038,609.6 -0.4021492354,53.3076224021,609.6 -0.4002657622,53.30438683049999,609.6 -0.3978371881,53.3012843609,609.6 -0.3948893466999999,53.2983478481,609.6 -0.3914535517,53.29560838279999,609.6 -0.3875662623,53.293094964,609.6 -0.3832686955,53.2908341927,609.6 -0.3786063882,53.2888499923,609.6 -0.3736287158,53.2871633562,609.6 -0.3683883700999999,53.2857921275,609.6 -0.3629408047,53.2847508108,609.6 -0.3573436505,53.2840504202,609.6 -0.3516561099,53.2836983632,609.6 -0.3459383346,53.2836983632,609.6 -0.3402507939,53.2840504202,609.6 -0.3346536397,53.2847508108,609.6 -0.3292060743,53.2857921275,609.6 -0.3239657287,53.2871633562,609.6 -0.3189880562,53.2888499923,609.6 -0.3143257489,53.2908341927,609.6 -0.3100281821,53.293094964,609.6 -0.3061408928,53.29560838279999,609.6 -0.3027050977,53.2983478481,609.6 -0.2997572563,53.3012843609,609.6 -0.2973286823,53.30438683049999,609.6 -0.295445209,53.3076224021,609.6 -0.294126912,53.3109568038,609.6 -0.2933878914,53.314354709,609.6 -0.2932361169,53.3177801097,609.6 -0.2936733382,53.3211966981,609.6 -0.2946950599,53.3245682512,609.6 -0.2962905833,53.3278590148,609.6 -0.2984431148,53.3310340837,609.6 -0.301129938,53.3340597721,609.6 -0.3043226511,53.3369039724,609.6 -0.3079874638,53.3395364964,609.6 -0.3120855537,53.34192939739999,609.6 -0.3165734767,53.3440572683,609.6 -0.3214036274,53.34589751230001,609.6 -0.3265247454,53.3474305843,609.6 -0.331882461,53.34864019969999,609.6 -0.337419875,53.3495135088,609.6 -0.3430781667,53.3500412334,609.6 -0.3487972222,53.3502177668,609.6 + + + + +
+ + EGRU322B WICKENBY RWY 03 + 531620N 0002232W -
531634N 0002321W -
531720N 0002245W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
531707N 0002156W -
531620N 0002232W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3756833332999999,53.27223333329999,609.6 -0.3654925278000001,53.2851925278,609.6 -0.3702002326000001,53.2862230041,609.6 -0.374734012,53.2875034333,609.6 -0.3790569999999999,53.2890234167,609.6 -0.3892416667,53.2760666667,609.6 -0.3756833332999999,53.27223333329999,609.6 + + + + +
+ + EGRU322C WICKENBY RWY 21 + 532142N 0001919W -
532128N 0001830W -
532041N 0001907W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
532055N 0001955W -
532142N 0001919W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3218611111,53.36162499999999,609.6 -0.3320773056,53.3486772222,609.6 -0.32736351,53.3476452269,609.6 -0.3228246477,53.34636297319999,609.6 -0.31849775,53.3448409167,609.6 -0.308275,53.35779166670001,609.6 -0.3218611111,53.36162499999999,609.6 + + + + +
+ + EGRU322D WICKENBY RWY 15 + 532121N 0002345W -
532137N 0002258W -
532051N 0002214W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
532035N 0002300W -
532121N 0002345W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3958777778,53.3559444444,609.6 -0.3834495556,53.3429619167,609.6 -0.3793878275,53.34472682669999,609.6 -0.3750764222,53.34626523630001,609.6 -0.3705505000000001,53.3475645833,609.6 -0.3828388889,53.3604055556,609.6 -0.3958777778,53.3559444444,609.6 + + + + +
+ + EGRU322E WICKENBY RWY 33 + 531643N 0001817W -
531627N 0001904W -
531709N 0001944W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531901N 0002056W to
531725N 0001857W -
531643N 0001817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3046611111,53.2785583333,609.6 -0.3157443333,53.2901840278,609.6 -0.3199044072,53.28850849060001,609.6 -0.3242993329,53.2870643575,609.6 -0.3288933611,53.2858633611,609.6 -0.3176722222,53.2740972222,609.6 -0.3046611111,53.2785583333,609.6 + + + + +
+ + EGRU323A CONINGSBY + A circle, 2.5 NM radius, centred at 530535N 0000958W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1661111111,53.1346591682,609.6 -0.1724940855,53.13448152419999,609.6 -0.1788224458,53.1339501119,609.6 -0.1850420493,53.1330694782,609.6 -0.1910996917,53.1318471572,609.6 -0.1969435658,53.1302936057,609.6 -0.2025237078,53.1284221129,609.6 -0.2077924272,53.1262486856,609.6 -0.2127047167,53.12379191059999,609.6 -0.2172186375,53.1210727944,609.6 -0.2212956789,53.1181145826,609.6 -0.2249010863,53.1149425597,609.6 -0.2280041568,53.11158383200001,609.6 -0.230578499,53.108067095,609.6 -0.2326022559,53.1044223867,609.6 -0.2340582872,53.1006808309,609.6 -0.2349343111,53.09687436990001,609.6 -0.2352230051,53.0930354918,609.6 -0.2349220625,53.0891969529,609.6 -0.234034207,53.08539149769999,609.6 -0.2325671642,53.0816515802,609.6 -0.2305335908,53.0780090869,609.6 -0.2279509613,53.0744950661,609.6 -0.2248414152,53.07113946340001,609.6 -0.2212315641,53.06797086779999,609.6 -0.2171522623,53.0650162689,609.6 -0.2126383414,53.0623008282,609.6 -0.2077283123,53.0598476661,609.6 -0.2024640366,53.0576776661,609.6 -0.1968903703,53.0558092983,609.6 -0.1910547834,53.054258463,609.6 -0.1850069576,53.053038357,609.6 -0.1787983656,53.0521593616,609.6 -0.1724818368,53.05162895519999,609.6 -0.1661111111,53.0514516503,609.6 -0.1597403854,53.05162895519999,609.6 -0.1534238567,53.0521593616,609.6 -0.1472152647,53.053038357,609.6 -0.1411674388,53.054258463,609.6 -0.1353318519,53.0558092983,609.6 -0.1297581856,53.0576776661,609.6 -0.1244939099,53.0598476661,609.6 -0.1195838808,53.0623008282,609.6 -0.1150699599,53.0650162689,609.6 -0.1109906581,53.06797086779999,609.6 -0.1073808071,53.07113946340001,609.6 -0.1042712609,53.0744950661,609.6 -0.1016886314,53.0780090869,609.6 -0.09965505799999999,53.0816515802,609.6 -0.0981880153,53.08539149769999,609.6 -0.0973001597,53.0891969529,609.6 -0.09699921709999999,53.0930354918,609.6 -0.09728791110000001,53.09687436990001,609.6 -0.09816393510000002,53.1006808309,609.6 -0.0996199663,53.1044223867,609.6 -0.1016437232,53.108067095,609.6 -0.1042180655,53.11158383200001,609.6 -0.1073211359,53.1149425597,609.6 -0.1109265433,53.1181145826,609.6 -0.1150035847,53.1210727944,609.6 -0.1195175056,53.12379191059999,609.6 -0.124429795,53.1262486856,609.6 -0.1296985144,53.1284221129,609.6 -0.1352786564,53.1302936057,609.6 -0.1411225305,53.1318471572,609.6 -0.1471801729,53.1330694782,609.6 -0.1533997764,53.1339501119,609.6 -0.1597281367,53.13448152419999,609.6 -0.1661111111,53.1346591682,609.6 + + + + +
+ + EGRU323B CONINGSBY RWY 07 + 530416N 0001515W -
530447N 0001532W -
530505N 0001402W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to
530434N 0001345W -
530416N 0001515W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2541946667,53.0711036389,609.6 -0.2291673333,53.0760418333,609.6 -0.2310417153,53.0788218642,609.6 -0.2325787151,53.0816759933,609.6 -0.2337702778,53.0845893889,609.6 -0.2588251667,53.0796456944,609.6 -0.2541946667,53.0711036389,609.6 + + + + +
+ + EGRU323C CONINGSBY RWY 25 + 530655N 0000441W -
530624N 0000424W -
530606N 0000555W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 530535N 0000958W to
530637N 0000611W -
530655N 0000441W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0779853056,53.1151844722,609.6 -0.1031692778,53.11025525,609.6 -0.1012750652,53.1074797611,609.6 -0.0997184131,53.104629315,609.6 -0.09850736110000001,53.10171875,609.6 -0.0733509722,53.1066424722,609.6 -0.0779853056,53.1151844722,609.6 + + + + +
+ + EGRU324A MONA + A circle, 2 NM radius, centred at 531533N 0042226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3740111111,53.29258197919999,609.6 -4.3797224662,53.2924054444,609.6 -4.3853731395,53.2918777155,609.6 -4.3909030984,53.2910043994,609.6 -4.3962536017,53.289794774,609.6 -4.4013678271,53.2882616893,609.6 -4.4061914781,53.28642143,609.6 -4.4106733634,53.2842935411,609.6 -4.4147659418,53.2819006196,609.6 -4.4184258276,53.2792680728,609.6 -4.4216142504,53.2764238474,609.6 -4.4242974655,53.2733981319,609.6 -4.4264471089,53.2702230341,609.6 -4.4280404944,53.2669322399,609.6 -4.4290608507,53.2635606551,609.6 -4.4294974932,53.26014403389999,609.6 -4.4293459322,53.25671859970001,609.6 -4.4286079143,53.2533206608,609.6 -4.4272913986,53.2499862254,609.6 -4.4254104656,53.2467506206,609.6 -4.4229851635,53.2436481187,609.6 -4.4200412909,53.2407115749,609.6 -4.416610119,53.2379720803,609.6 -4.4127280581,53.2354586342,609.6 -4.4084362697,53.2331978382,609.6 -4.4037802294,53.2312136158,609.6 -4.3988092463,53.229526961,609.6 -4.3935759418,53.2281557169,609.6 -4.388135695,53.2271143885,609.6 -4.3825460595,53.2264139899,609.6 -4.3768661586,53.226061929,609.6 -4.3711560636,53.226061929,609.6 -4.3654761627,53.2264139899,609.6 -4.3598865272,53.2271143885,609.6 -4.3544462804,53.2281557169,609.6 -4.3492129759,53.229526961,609.6 -4.3442419928,53.2312136158,609.6 -4.3395859526,53.2331978382,609.6 -4.3352941641,53.2354586342,609.6 -4.3314121032,53.2379720803,609.6 -4.3279809314,53.2407115749,609.6 -4.3250370587,53.2436481187,609.6 -4.3226117567,53.2467506206,609.6 -4.3207308237,53.2499862254,609.6 -4.3194143079,53.2533206608,609.6 -4.3186762901,53.25671859970001,609.6 -4.318524729,53.26014403389999,609.6 -4.3189613715,53.2635606551,609.6 -4.3199817278,53.2669322399,609.6 -4.3215751134,53.2702230341,609.6 -4.3237247567,53.2733981319,609.6 -4.3264079718,53.2764238474,609.6 -4.3295963947,53.2792680728,609.6 -4.3332562804,53.2819006196,609.6 -4.3373488588,53.2842935411,609.6 -4.3418307441,53.28642143,609.6 -4.3466543951,53.2882616893,609.6 -4.3517686205,53.289794774,609.6 -4.3571191238,53.2910043994,609.6 -4.3626490828,53.2918777155,609.6 -4.3682997561,53.2924054444,609.6 -4.3740111111,53.29258197919999,609.6 + + + + +
+ + EGRU324B MONA RWY 04 + 531255N 0042513W -
531315N 0042556W -
531409N 0042448W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to
531349N 0042405W -
531255N 0042513W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4203648889,53.2153488889,609.6 -4.40135675,53.2303406667,609.6 -4.4055967384,53.2319366862,609.6 -4.4095800249,53.23375540819999,609.6 -4.4132741944,53.2357820556,609.6 -4.4322736944,53.2207938056,609.6 -4.4203648889,53.2153488889,609.6 + + + + +
+ + EGRU324C MONA RWY 22 + 531813N 0041938W -
531753N 0041855W -
531658N 0042005W thence anti-clockwise by the arc of a circle radius 2 NM centred on 531533N 0042226W to
531718N 0042048W -
531813N 0041938W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3271375,53.30356372220001,609.6 -4.34662625,53.2882521389,609.6 -4.3423830117,53.2866539207,609.6 -4.3383978058,53.2848328586,609.6 -4.3347031111,53.2828038056,609.6 -4.3152056667,53.2981188889,609.6 -4.3271375,53.30356372220001,609.6 + + + + +
+ + EGRU325 HMP ALTCOURSE + 532802N 0025617W -
532801N 0025600W -
532751N 0025537W -
532734N 0025532W -
532725N 0025547W -
532726N 0025636W -
532740N 0025641W -
532753N 0025641W -
532802N 0025617W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 86 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.93805,53.4670833333,152.4 -2.9446055556,53.4648444444,152.4 -2.9447194444,53.46123333330001,152.4 -2.9432222222,53.4572638889,152.4 -2.9298333333,53.4570138889,152.4 -2.9254722222,53.4595444444,152.4 -2.926844444399999,53.4641,152.4 -2.9333222222,53.46705,152.4 -2.93805,53.4670833333,152.4 + + + + +
+ + EGRU326 HMP ASKHAM GRANGE + 535551N 0011124W -
535552N 0011041W -
535537N 0011031W -
535520N 0011046W -
535516N 0011105W -
535520N 0011123W -
535539N 0011137W -
535551N 0011124W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 104 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1900611111,53.9308583333,182.88 -1.1936361111,53.9275305556,182.88 -1.1895888889,53.9222666667,182.88 -1.1848388889,53.9211972222,182.88 -1.1794583333,53.9221,182.88 -1.1751583333,53.9269861111,182.88 -1.1780777778,53.9311083333,182.88 -1.1900611111,53.9308583333,182.88 + + + + +
+ + EGRU327 HMP BERWYN + 530233N 0025539W -
530210N 0025453W -
530137N 0025537W -
530159N 0025625W -
530233N 0025539W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 118 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.927375,53.0424444444,182.88 -2.9403833333,53.0330111111,182.88 -2.9270166667,53.0268944444,182.88 -2.9147805556,53.0362027778,182.88 -2.927375,53.0424444444,182.88 + + + + +
+ + EGRU328 HMP BUCKLEY HALL + 533825N 0020916W -
533826N 0020823W -
533805N 0020814W -
533754N 0020816W -
533744N 0020841W -
533758N 0020909W -
533825N 0020916W
Upper limit: 1000 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 585 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.154525,53.6402944444,304.8 -2.1525222222,53.6327444444,304.8 -2.1448333333,53.6288722222,304.8 -2.1377555556,53.6317027778,304.8 -2.1370972222,53.6348333333,304.8 -2.1397833333,53.6406194444,304.8 -2.154525,53.6402944444,304.8 + + + + +
+ + EGRU329 HMP DONCASTER + 533154N 0010840W -
533130N 0010807W -
533104N 0010843W -
533126N 0010928W -
533154N 0010840W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 55 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.1444388889,53.5315583333,152.4 -1.1577666667,53.52399444440001,152.4 -1.1453638889,53.51771944439999,152.4 -1.1354083333,53.5251083333,152.4 -1.1444388889,53.5315583333,152.4 + + + + +
+ + EGRU330 HMP FOREST BANK + 533113N 0021811W -
533102N 0021732W -
533047N 0021730W -
533029N 0021808W -
533056N 0021847W -
533113N 0021811W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 128 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.3030138889,53.5202,182.88 -2.3129333333,53.51568333329999,182.88 -2.3022722222,53.5080277778,182.88 -2.2917777778,53.51300833330001,182.88 -2.2921805556,53.5171638889,182.88 -2.3030138889,53.5202,182.88 + + + + +
+ + EGRU331 HMP FULL SUTTON + 535923N 0005234W -
535920N 0005134W -
535842N 0005138W -
535845N 0005239W -
535923N 0005234W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 57 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.8760472222,53.9896138889,152.4 -0.8775861111,53.979075,152.4 -0.8606055556000001,53.97820000000001,152.4 -0.8593111110999999,53.98882222219999,152.4 -0.8760472222,53.9896138889,152.4 + + + + +
+ + EGRU332 HMP GARTH/WYMOTT + 534108N 0024604W -
534108N 0024455W -
534103N 0024428W -
534023N 0024424W -
534022N 0024529W -
534033N 0024603W -
534108N 0024604W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 50 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7676833333,53.68546666670001,152.4 -2.7675444444,53.6757666667,152.4 -2.7581694444,53.67288333330001,152.4 -2.7399944444,53.6731444444,152.4 -2.7410666667,53.68416111110001,152.4 -2.7487361111,53.6856027778,152.4 -2.7676833333,53.68546666670001,152.4 + + + + +
+ + EGRU333 HMP HINDLEY + 533127N 0023410W -
533057N 0023356W -
533048N 0023459W -
533119N 0023510W -
533127N 0023410W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 127 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5694444444,53.5242805556,182.88 -2.5862361111,53.5218611111,182.88 -2.5829361111,53.5132916667,182.88 -2.5656388889,53.51574722220001,182.88 -2.5694444444,53.5242805556,182.88 + + + + +
+ + EGRU334 HMP HULL + 534518N 0001815W -
534518N 0001708W -
534458N 0001709W -
534439N 0001732W -
534439N 0001817W -
534518N 0001815W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 17 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3041611111,53.7549277778,152.4 -0.3046055556,53.7440388889,152.4 -0.2920833333,53.74415,152.4 -0.2857472222,53.7494888889,152.4 -0.2854222222,53.75506388889999,152.4 -0.3041611111,53.7549277778,152.4 + + + + +
+ + EGRU335 HMP HUMBER + 534633N 0003818W -
534627N 0003753W -
534605N 0003727W -
534549N 0003759W -
534550N 0003846W -
534617N 0003904W -
534633N 0003818W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 71 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6382388889,53.7757222222,152.4 -0.6510861111,53.7714277778,152.4 -0.6461416667,53.7639166667,152.4 -0.6329944444,53.7635388889,152.4 -0.6240388889,53.7680166667,152.4 -0.6313444444,53.7741194444,152.4 -0.6382388889,53.7757222222,152.4 + + + + +
+ + EGRU336 HMP LEEDS + 534805N 0013438W -
534758N 0013410W -
534733N 0013407W -
534727N 0013438W -
534739N 0013509W -
534801N 0013501W -
534805N 0013438W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 245 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5773277778,53.8012805556,213.36 -1.5836694444,53.8002944444,213.36 -1.5858305556,53.7941166667,213.36 -1.5771444444,53.7907694444,213.36 -1.5686861111,53.79243611110001,213.36 -1.5694972222,53.7994833333,213.36 -1.5773277778,53.8012805556,213.36 + + + + +
+ + EGRU337 HMP LINCOLN + 531426N 0003115W -
531422N 0003038W -
531400N 0003032W -
531350N 0003046W -
531353N 0003122W -
531401N 0003132W -
531415N 0003132W -
531426N 0003115W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Restricted Area (EGR313) Waddington and HMPPS.
Contact: RAF Waddington Station Ops 01522-726532 or email: wad-stationops@mod.gov.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 163 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5207194444,53.24055,182.88 -0.5256916667,53.2375583333,182.88 -0.5254333333,53.23372777779999,182.88 -0.5227000000000001,53.2314527778,182.88 -0.5127777778,53.23064444440001,182.88 -0.5089916667,53.2332305556,182.88 -0.5106000000000001,53.2393777778,182.88 -0.5207194444,53.24055,182.88 + + + + +
+ + EGRU338 HMP LINDHOLME/MOORLAND + 533313N 0005850W -
533311N 0005732W -
533254N 0005713W -
533214N 0005733W -
533219N 0005853W -
533313N 0005850W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 29 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9806055556,53.5535833333,152.4 -0.9814833333,53.53871666669999,152.4 -0.9591083333,53.5372694444,152.4 -0.9536722222,53.54842222220001,152.4 -0.9588222222,53.5530611111,152.4 -0.9806055556,53.5535833333,152.4 + + + + +
+ + EGRU339 HMP LIVERPOOL + 532740N 0025848W -
532750N 0025753W -
532742N 0025741W -
532719N 0025731W -
532706N 0025834W -
532740N 0025848W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.980019444399999,53.4611777778,182.88 -2.9762333333,53.4516722222,182.88 -2.9585833333,53.4552138889,182.88 -2.9614138889,53.4616583333,182.88 -2.964752777799999,53.4638861111,182.88 -2.980019444399999,53.4611777778,182.88 + + + + +
+ + EGRU340 HMP LOWDHAM GRANGE + 530115N 0010219W -
530110N 0010156W -
530055N 0010149W -
530039N 0010203W -
530035N 0010234W -
530052N 0010258W -
530108N 0010247W -
530115N 0010219W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 281 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.0387222222,53.0207638889,213.36 -1.04635,53.0188944444,213.36 -1.0495444444,53.0145166667,213.36 -1.0426388889,53.0096305556,213.36 -1.0340305556,53.010775,213.36 -1.0301833333,53.0151972222,213.36 -1.0323027778,53.019425,213.36 -1.0387222222,53.0207638889,213.36 + + + + +
+ + EGRU341 HMP MANCHESTER + 533000N 0021509W -
532957N 0021446W -
532943N 0021414W -
532929N 0021413W -
532919N 0021435W -
532916N 0021448W -
532920N 0021507W -
532937N 0021520W -
533000N 0021509W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 153 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2525083333,53.5000555556,182.88 -2.2556861111,53.4935416667,182.88 -2.2519944444,53.4887888889,182.88 -2.2465805556,53.4877444444,182.88 -2.242975,53.4886138889,182.88 -2.2370361111,53.4915083333,182.88 -2.2373111111,53.4954055556,182.88 -2.246225,53.4992083333,182.88 -2.2525083333,53.5000555556,182.88 + + + + +
+ + EGRU342 HMP MORTON HALL + 531026N 0004128W -
531021N 0004043W -
530946N 0004034W -
530938N 0004054W -
530942N 0004135W -
531008N 0004144W -
531026N 0004128W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 79 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.6910888889,53.1738,152.4 -0.6956666667,53.16876666669999,152.4 -0.6930166667,53.1615611111,152.4 -0.6816,53.16058055559999,152.4 -0.6761861111,53.1627138889,152.4 -0.6785611110999999,53.1725222222,152.4 -0.6910888889,53.1738,152.4 + + + + +
+ + EGRU343 HMP NEW HALL + 533826N 0013700W -
533826N 0013620W -
533811N 0013613W -
533753N 0013618W -
533752N 0013640W -
533800N 0013716W -
533818N 0013719W -
533826N 0013700W
Upper limit: 900 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 458 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6165638889,53.6405861111,274.32 -1.6218666667,53.63846944439999,274.32 -1.6211555556,53.63321944439999,274.32 -1.6110805556,53.6311361111,274.32 -1.6048611111,53.6312833333,274.32 -1.6036416667,53.63649444440001,274.32 -1.6056888889,53.6405777778,274.32 -1.6165638889,53.6405861111,274.32 + + + + +
+ + EGRU344 HMP PRESTON + 534606N 0024105W -
534537N 0024043W -
534525N 0024124W -
534538N 0024149W -
534555N 0024139W -
534606N 0024105W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 147 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6846,53.7683555556,182.88 -2.6940861111,53.7653888889,182.88 -2.6968777778,53.7606694444,182.88 -2.6900666667,53.75699722219999,182.88 -2.6785833333,53.760175,182.88 -2.6846,53.7683555556,182.88 + + + + +
+ + EGRU345 HMP RANBY + 531943N 0005946W -
531922N 0005920W -
531858N 0005925W -
531903N 0010035W -
531926N 0010034W -
531943N 0005946W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 153 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.9960666667,53.32866666670001,182.88 -1.009525,53.32382777779999,182.88 -1.0096972222,53.31741388890001,182.88 -0.9902694444,53.31601944439999,182.88 -0.9887527778,53.3227777778,182.88 -0.9960666667,53.32866666670001,182.88 + + + + +
+ + EGRU346 HMP RISLEY + 532638N 0023135W -
532635N 0023109W -
532624N 0023059W -
532602N 0023050W -
532558N 0023204W -
532625N 0023154W -
532638N 0023135W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 126 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.5262638889,53.4438638889,182.88 -2.5317916667,53.4401555556,182.88 -2.5344305556,53.4327611111,182.88 -2.5137916667,53.4338666667,182.88 -2.5162555556,53.43994166670001,182.88 -2.5190416667,53.44307499999999,182.88 -2.5262638889,53.4438638889,182.88 + + + + +
+ + EGRU347 HMP STYAL + 532043N 0021412W -
532031N 0021342W -
532010N 0021357W -
532005N 0021442W -
532019N 0021500W -
532038N 0021441W -
532043N 0021412W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 271 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2365972222,53.34522222220001,213.36 -2.2448416667,53.34383055559999,213.36 -2.2500166667,53.3386916667,213.36 -2.2451083333,53.3347666667,213.36 -2.2324833333,53.33602222220001,213.36 -2.2282388889,53.3418388889,213.36 -2.2365972222,53.34522222220001,213.36 + + + + +
+ + EGRU348 HMP WAKEFIELD + 534112N 0013105W -
534118N 0013027W -
534051N 0012947W -
534035N 0013042W -
534054N 0013104W -
534112N 0013105W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 117 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5180833333,53.68662777779999,182.88 -1.5176888889,53.6818027778,182.88 -1.511725,53.67625,182.88 -1.4965,53.68073055560001,182.88 -1.5075333333,53.6883444444,182.88 -1.5180833333,53.68662777779999,182.88 + + + + +
+ + EGRU349 HMP WEALSTUN + 535520N 0011957W -
535515N 0011917W -
535456N 0011909W -
535432N 0011932W -
535432N 0011955W -
535443N 0012021W -
535454N 0012018W -
535506N 0012011W -
535520N 0011957W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 104 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.33255,53.92216111110001,182.88 -1.3364861111,53.9183027778,182.88 -1.3382055556,53.9151166667,182.88 -1.3392722222,53.9119583333,182.88 -1.3319944444,53.9089,182.88 -1.3256611111,53.9087638889,182.88 -1.3190305556,53.9155222222,182.88 -1.3214888889,53.9207194444,182.88 -1.33255,53.92216111110001,182.88 + + + + +
+ + EGRU350 HMP WERRINGTON + 530135N 0020538W -
530140N 0020507W -
530131N 0020450W -
530108N 0020437W -
530100N 0020530W -
530118N 0020540W -
530135N 0020538W
Upper limit: 1300 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 834 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.0938416667,53.02645833329999,396.24 -2.094375,53.02160555559999,396.24 -2.0916583333,53.0165722222,396.24 -2.0768916667,53.01876111109999,396.24 -2.0805333333,53.0252555556,396.24 -2.0854083333,53.0276388889,396.24 -2.0938416667,53.02645833329999,396.24 + + + + +
+ + EGRU351 HMP WETHERBY + 535628N 0012218W -
535633N 0012138W -
535557N 0012124W -
535551N 0012229W -
535616N 0012241W -
535623N 0012221W -
535628N 0012218W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 89 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3716555556,53.9410944444,152.4 -1.3724861111,53.93978888889999,152.4 -1.3780666667,53.9377611111,152.4 -1.3747638889,53.93088611110001,152.4 -1.3567138889,53.93245555560001,152.4 -1.3605833333,53.9424916667,152.4 -1.3716555556,53.9410944444,152.4 + + + + +
+ + EGRU401A ENNISKILLEN/ST ANGELO + A circle, 2 NM radius, centred at 542355N 0073907W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.651894444400001,54.4319645097,609.6 -7.6577631133,54.4317880028,609.6 -7.6635694228,54.4312603575,609.6 -7.669251681100001,54.4303871803,609.6 -7.674749523699999,54.4291777486,609.6 -7.680004558999999,54.4276449115,609.6 -7.6849609919,54.4258049525,609.6 -7.6895662193,54.42367741499999,609.6 -7.6937713903,54.4212848941,609.6 -7.697531925499999,54.41865279449999,609.6 -7.7008079893,54.41580906029999,609.6 -7.7035649119,54.4127838759,609.6 -7.7057735534,54.4096093453,609.6 -7.7074106097,54.40631914959999,609.6 -7.7084588548,54.4029481892,609.6 -7.7089073179,54.39953221220001,609.6 -7.7087513939,54.3961074356,609.6 -7.7079928858,54.39271016040001,609.6 -7.706639979299999,54.38937638760001,609.6 -7.7047071497,54.3861414363,609.6 -7.7022150032,54.38303957069999,609.6 -7.6991900532,54.380103638,609.6 -7.6956644351,54.3773647213,609.6 -7.691675563,54.37485181190001,609.6 -7.6872657315,54.372591504,609.6 -7.6824816662,54.3706077142,609.6 -7.677374029799999,54.3689214302,609.6 -7.6719968874,54.3675504896,609.6 -7.6664071357,54.366509393,609.6 -7.660663905299999,54.36580915089999,609.6 -7.6548279383,54.3654571688,609.6 -7.6489609506,54.3654571688,609.6 -7.6431249836,54.36580915089999,609.6 -7.6373817532,54.366509393,609.6 -7.6317920015,54.3675504896,609.6 -7.626414859,54.3689214302,609.6 -7.6213072227,54.3706077142,609.6 -7.6165231574,54.372591504,609.6 -7.6121133258,54.37485181190001,609.6 -7.6081244538,54.3773647213,609.6 -7.6045988357,54.380103638,609.6 -7.6015738857,54.38303957069999,609.6 -7.5990817392,54.3861414363,609.6 -7.5971489096,54.38937638760001,609.6 -7.595796003,54.39271016040001,609.6 -7.5950374949,54.3961074356,609.6 -7.594881571000001,54.39953221220001,609.6 -7.5953300341,54.4029481892,609.6 -7.5963782792,54.40631914959999,609.6 -7.5980153355,54.4096093453,609.6 -7.600223977,54.4127838759,609.6 -7.6029808996,54.41580906029999,609.6 -7.6062569634,54.41865279449999,609.6 -7.610017498500001,54.4212848941,609.6 -7.6142226696,54.42367741499999,609.6 -7.618827897,54.4258049525,609.6 -7.6237843299,54.4276449115,609.6 -7.6290393652,54.4291777486,609.6 -7.6345372078,54.4303871803,609.6 -7.6402194661,54.4312603575,609.6 -7.6460257756,54.4317880028,609.6 -7.651894444400001,54.4319645097,609.6 + + + + +
+ + EGRU401B ENNISKILLEN/ST ANGELO RWY 14 + 542602N 0074247W -
542623N 0074205W -
542536N 0074057W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to
542515N 0074139W -
542602N 0074247W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.713088888899999,54.4338694444,609.6 -7.694273,54.4209643056,609.6 -7.6906578306,54.4231026591,609.6 -7.6867264144,54.42504212379999,609.6 -7.6825108056,54.4267668889,609.6 -7.7013388889,54.4396833333,609.6 -7.713088888899999,54.4338694444,609.6 + + + + +
+ + EGRU401C ENNISKILLEN/ST ANGELO RWY 32 + 542152N 0073531W -
542131N 0073613W -
542214N 0073716W thence anti-clockwise by the arc of a circle radius 2 NM centred on 542355N 0073907W to
542235N 0073634W -
542152N 0073531W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.591830555599999,54.36440277780001,609.6 -7.6093981667,54.37650480560001,609.6 -7.61299728,54.3743600838,609.6 -7.6169125119,54.3724133666,609.6 -7.621112,54.3706804722,609.6 -7.6035555556,54.3585888889,609.6 -7.591830555599999,54.36440277780001,609.6 + + + + +
+ + EGRU402A BELFAST ALDERGROVE + A circle, 2.5 NM radius, centred at 543927N 0061257W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2158333333,54.69909270639999,609.6 -6.2224594592,54.6989150989,609.6 -6.229028880999999,54.698383796,609.6 -6.2354853842,54.6975033443,609.6 -6.2417737294,54.69628127790001,609.6 -6.2478401287,54.6947280529,609.6 -6.2536327092,54.69285695770001,609.6 -6.2591019599,54.6906839982,609.6 -6.2642011568,54.6882277598,609.6 -6.2688867638,54.6855092472,609.6 -6.2731188056,54.68255170359999,609.6 -6.2768612078,54.6793804105,609.6 -6.2800821046,54.6760224706,609.6 -6.2827541076,54.672506575,609.6 -6.284854537200001,54.6688627568,609.6 -6.2863656112,54.6651221334,609.6 -6.287274592499999,54.6613166408,609.6 -6.2875738922,54.6574787594,609.6 -6.2872611287,54.6536412373,609.6 -6.286339141999999,54.6498368101,609.6 -6.284815964100001,54.6460979221,609.6 -6.2827047442,54.6424564499,609.6 -6.2800236317,54.6389434314,609.6 -6.2767956168,54.6355888016,609.6 -6.273048329999999,54.6324211387,609.6 -6.268813803699999,54.62946742190001,609.6 -6.2641281966,54.6267528025,609.6 -6.2590314843,54.6243003909,609.6 -6.253567118099999,54.6221310617,609.6 -6.247781655799999,54.62026327660001,609.6 -6.2417243659,54.6187129286,609.6 -6.235446811099999,54.6174932083,609.6 -6.2290024118,54.616614492,609.6 -6.2224459954,54.6160842545,609.6 -6.2158333333,54.6159070062,609.6 -6.2092206713,54.6160842545,609.6 -6.2026642549,54.616614492,609.6 -6.196219855600001,54.6174932083,609.6 -6.1899423008,54.6187129286,609.6 -6.183885010900001,54.62026327660001,609.6 -6.178099548500001,54.6221310617,609.6 -6.1726351824,54.6243003909,609.6 -6.1675384701,54.6267528025,609.6 -6.162852863000001,54.62946742190001,609.6 -6.158618336699999,54.6324211387,609.6 -6.1548710499,54.6355888016,609.6 -6.151643035,54.6389434314,609.6 -6.1489619225,54.6424564499,609.6 -6.1468507026,54.6460979221,609.6 -6.145327524599999,54.6498368101,609.6 -6.144405538,54.6536412373,609.6 -6.1440927744,54.6574787594,609.6 -6.144392074200001,54.6613166408,609.6 -6.1453010555,54.6651221334,609.6 -6.146812129499999,54.6688627568,609.6 -6.148912559,54.672506575,609.6 -6.151584562100001,54.6760224706,609.6 -6.1548054589,54.6793804105,609.6 -6.1585478611,54.68255170359999,609.6 -6.1627799028,54.6855092472,609.6 -6.167465509900001,54.6882277598,609.6 -6.1725647068,54.6906839982,609.6 -6.1780339574,54.69285695770001,609.6 -6.183826538,54.6947280529,609.6 -6.1898929372,54.69628127790001,609.6 -6.1961812825,54.6975033443,609.6 -6.202637785700001,54.698383796,609.6 -6.2092072075,54.6989150989,609.6 -6.2158333333,54.69909270639999,609.6 + + + + +
+ + EGRU402B BELFAST ALDERGROVE RWY 07 + 543745N 0061808W -
543815N 0061831W -
543839N 0061702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
543810N 0061638W -
543745N 0061808W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3021944444,54.6292277778,609.6 -6.2772079722,54.63597916669999,609.6 -6.2797248099,54.63860010039999,609.6 -6.2819096729,54.6413194151,609.6 -6.283751166700001,54.6441229722,609.6 -6.3087138889,54.6373777778,609.6 -6.3021944444,54.6292277778,609.6 + + + + +
+ + EGRU402C BELFAST ALDERGROVE RWY 25 + 544109N 0060745W -
544039N 0060721W -
544015N 0060852W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
544044N 0060916W -
544109N 0060745W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.129130555600001,54.68573888889999,609.6 -6.1543686389,54.6789653889,609.6 -6.1518605176,54.6763409319,609.6 -6.1496856953,54.67361848979999,609.6 -6.147855416699999,54.67081225,609.6 -6.1225944444,54.6775916667,609.6 -6.129130555600001,54.68573888889999,609.6 + + + + +
+ + EGRU402D BELFAST ALDERGROVE RWY 17 + 544157N 0061536W -
544207N 0061443W -
544146N 0061431W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
544131N 0061521W -
544157N 0061536W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2600159167,54.6992365556,609.6 -6.255936416699999,54.6919939444,609.6 -6.2514765225,54.69360131199999,609.6 -6.246825361899999,54.69501532780001,609.6 -6.2420078889,54.69622841670001,609.6 -6.2452674167,54.70201877779999,609.6 -6.2600159167,54.6992365556,609.6 + + + + +
+ + EGRU402E BELFAST ALDERGROVE RWY 35 + 543604N 0061119W -
543554N 0061212W -
543657N 0061247W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543927N 0061257W to
543702N 0061152W -
543604N 0061119W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.188672249999999,54.6012328056,609.6 -6.1976555556,54.61726572220001,609.6 -6.2027725007,54.6166028186,609.6 -6.207959133699999,54.6161585674,609.6 -6.213187777799999,54.6159353333,609.6 -6.2033843056,54.59845055560001,609.6 -6.188672249999999,54.6012328056,609.6 + + + + +
+ + EGRU403A BELFAST/CITY + A circle, 2 NM radius, centred at 543705N 0055221W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.8725,54.6513299617,609.6 -5.8784002309,54.65115346009999,609.6 -5.8842377659,54.6506258306,609.6 -5.8899505801,54.6497526798,609.6 -5.8954779834,54.64854328479999,609.6 -5.9007612692,54.6470104947,609.6 -5.905744341999999,54.6451705926,609.6 -5.9103743152,54.64304312179999,609.6 -5.9146020751,54.6406506769,609.6 -5.9183828029,54.63801866239999,609.6 -5.9216764494,54.6351750215,609.6 -5.9244481591,54.63214993830001,609.6 -5.9266686364,54.62897551569999,609.6 -5.928314453399999,54.62568543410001,609.6 -5.929368292899999,54.62231459280001,609.6 -5.9298191266,54.6188987388,609.6 -5.929662326399999,54.6154740878,609.6 -5.928899706500001,54.6120769396,609.6 -5.927539498300001,54.60874329349999,609.6 -5.9255962562,54.6055084673,609.6 -5.9230906984,54.6024067236,609.6 -5.920049481799999,54.5994709081,609.6 -5.916504915099999,54.5967321021,609.6 -5.912494614,54.5942192958,609.6 -5.9080611001,54.5919590816,609.6 -5.90325135,54.5899753748,609.6 -5.898116298,54.588289162,609.6 -5.892710298600001,54.5869182798,609.6 -5.8870905533,54.5858772276,609.6 -5.8813165087,54.5851770156,609.6 -5.875449231699999,54.58482504860001,609.6 -5.8695507683,54.58482504860001,609.6 -5.863683491299999,54.5851770156,609.6 -5.857909446700001,54.5858772276,609.6 -5.8522897014,54.5869182798,609.6 -5.846883702,54.588289162,609.6 -5.84174865,54.5899753748,609.6 -5.836938899899999,54.5919590816,609.6 -5.832505386,54.5942192958,609.6 -5.8284950849,54.5967321021,609.6 -5.824950518200001,54.5994709081,609.6 -5.8219093016,54.6024067236,609.6 -5.8194037438,54.6055084673,609.6 -5.8174605017,54.60874329349999,609.6 -5.8161002935,54.6120769396,609.6 -5.8153376736,54.6154740878,609.6 -5.815180873400001,54.6188987388,609.6 -5.815631707100001,54.62231459280001,609.6 -5.8166855466,54.62568543410001,609.6 -5.8183313636,54.62897551569999,609.6 -5.820551840900001,54.63214993830001,609.6 -5.823323550599999,54.6351750215,609.6 -5.826617197099999,54.63801866239999,609.6 -5.8303979249,54.6406506769,609.6 -5.8346256848,54.64304312179999,609.6 -5.839255658,54.6451705926,609.6 -5.844238730799999,54.6470104947,609.6 -5.8495220166,54.64854328479999,609.6 -5.8550494199,54.6497526798,609.6 -5.8607622341,54.6506258306,609.6 -5.8665997691,54.65115346009999,609.6 -5.8725,54.6513299617,609.6 + + + + +
+ + EGRU403B BELFAST/CITY RWY 04 + 543421N 0055503W -
543440N 0055549W -
543537N 0055441W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to
543518N 0055355W -
543421N 0055503W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.9174916667,54.5725666667,609.6 -5.898566388899999,54.5884211389,609.6 -5.9030612095,54.5899055038,609.6 -5.9073076397,54.5916190103,609.6 -5.9112711389,54.5935477222,609.6 -5.9301944444,54.5776916667,609.6 -5.9174916667,54.5725666667,609.6 + + + + +
+ + EGRU403C BELFAST/CITY RWY 22 + 543951N 0054936W -
543933N 0054850W -
543833N 0055002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543705N 0055221W to
543852N 0055047W -
543951N 0054936W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.8266055556,54.6643027778,609.6 -5.8464906111,54.6477122778,609.6 -5.8419875834,54.6462309714,609.6 -5.8377334708,54.6445201629,609.6 -5.8337629444,54.6425938056,609.6 -5.813875000000001,54.6591833333,609.6 -5.8266055556,54.6643027778,609.6 + + + + +
+ + EGRU404A NEWTOWNARDS + A circle, 2 NM radius, centred at 543452N 0054131W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6919444444,54.6143857216,609.6 -5.697839330000001,54.6142092191,609.6 -5.7036715766,54.61368158700001,609.6 -5.709379215799999,54.6128084317,609.6 -5.7149016127,54.6115990305,609.6 -5.720180114,54.6100662325,609.6 -5.725158675,54.6082263209,609.6 -5.7297844573,54.6060988389,609.6 -5.7340083916,54.60370638119999,609.6 -5.737785699500001,54.6010743524,609.6 -5.741076368299999,54.59823069580001,609.6 -5.7438455736,54.59520559560001,609.6 -5.746064046399999,54.5920311548,609.6 -5.7477083797,54.5887410541,609.6 -5.748761271699999,54.5853701927,609.6 -5.749211704000001,54.581954318,609.6 -5.7490550522,54.5785296459,609.6 -5.7482931288,54.5751324763,609.6 -5.7469341571,54.5717988089,609.6 -5.744992678500001,54.5685639616,609.6 -5.7424893921,54.5654621975,609.6 -5.7394509304,54.5625263622,609.6 -5.7359095728,54.55978753760001,609.6 -5.7319029009,54.5572747139,609.6 -5.727473397900001,54.55501448390001,609.6 -5.7226679978,54.5530307632,609.6 -5.7175375889,54.5513445384,609.6 -5.712136476699999,54.5499736463,609.6 -5.7065218111,54.5489325867,609.6 -5.7007529851,54.5482323696,609.6 -5.6948910108,54.5478804001,609.6 -5.6889978781,54.5478804001,609.6 -5.6831359038,54.5482323696,609.6 -5.6773670778,54.5489325867,609.6 -5.6717524122,54.5499736463,609.6 -5.6663513,54.5513445384,609.6 -5.6612208911,54.5530307632,609.6 -5.656415491,54.55501448390001,609.6 -5.651985987899999,54.5572747139,609.6 -5.647979316099999,54.55978753760001,609.6 -5.6444379585,54.5625263622,609.6 -5.641399496799999,54.5654621975,609.6 -5.6388962103,54.5685639616,609.6 -5.6369547318,54.5717988089,609.6 -5.635595760099999,54.5751324763,609.6 -5.634833836699999,54.5785296459,609.6 -5.634677184900001,54.581954318,609.6 -5.6351276172,54.5853701927,609.6 -5.636180509199999,54.5887410541,609.6 -5.6378248425,54.5920311548,609.6 -5.6400433153,54.59520559560001,609.6 -5.6428125206,54.59823069580001,609.6 -5.6461031894,54.6010743524,609.6 -5.6498804973,54.60370638119999,609.6 -5.6541044316,54.6060988389,609.6 -5.6587302139,54.6082263209,609.6 -5.6637087749,54.6100662325,609.6 -5.6689872762,54.6115990305,609.6 -5.6745096731,54.6128084317,609.6 -5.680217312300001,54.61368158700001,609.6 -5.6860495589,54.6142092191,609.6 -5.6919444444,54.6143857216,609.6 + + + + +
+ + EGRU404B NEWTOWNARDS RWY 03 + 543214N 0054343W -
543231N 0054430W -
543319N 0054340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543302N 0054253W -
543214N 0054343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7285722222,54.5372,609.6 -5.7146738611,54.5505698333,609.6 -5.719318224,54.5518842841,609.6 -5.7237401423,54.5534366053,609.6 -5.7279036667,54.5552141667,609.6 -5.741791666700001,54.54185,609.6 -5.7285722222,54.5372,609.6 + + + + +
+ + EGRU404C NEWTOWNARDS RWY 21 + 543727N 0053922W -
543710N 0053834W -
543625N 0053921W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543642N 0054009W -
543727N 0053922W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6560305556,54.6242111111,609.6 -5.6691476389,54.6116395833,609.6 -5.6644993349,54.6103214286,609.6 -5.660075022000001,54.6087652411,609.6 -5.6559107778,54.6069837222,609.6 -5.642783333299999,54.6195611111,609.6 -5.6560305556,54.6242111111,609.6 + + + + +
+ + EGRU404D NEWTOWNARDS RWY 08 + 543356N 0054615W -
543428N 0054627W -
543440N 0054456W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543408N 0054443W -
543356N 0054615W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.770788888900001,54.56556388890001,609.6 -5.7453074167,54.5690223611,609.6 -5.746967770199999,54.5718659434,609.6 -5.7481803273,54.57478490070001,609.6 -5.748935138900001,54.5777554722,609.6 -5.7742916667,54.5743138889,609.6 -5.770788888900001,54.56556388890001,609.6 + + + + +
+ + EGRU404E NEWTOWNARDS RWY 26 + 543545N 0053655W -
543513N 0053642W -
543502N 0053806W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543534N 0053818W -
543545N 0053655W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6151472222,54.5958166667,609.6 -5.6382448611,54.5927102222,609.6 -5.636664830199999,54.5898510472,609.6 -5.635535265300001,54.5869207834,609.6 -5.634865277800001,54.5839433056,609.6 -5.6116416667,54.5870666667,609.6 -5.6151472222,54.5958166667,609.6 + + + + +
+ + EGRU404F NEWTOWNARDS RWY 15 + 543716N 0054418W -
543733N 0054330W -
543645N 0054241W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543630N 0054331W -
543716N 0054418W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.738344444400001,54.6211611111,609.6 -5.7251928056,54.6082122222,609.6 -5.7208435871,54.60984465680001,609.6 -5.716257972799999,54.6112424062,609.6 -5.711473444400001,54.6123940278,609.6 -5.7250027778,54.6257194444,609.6 -5.738344444400001,54.6211611111,609.6 + + + + +
+ + EGRU404G NEWTOWNARDS RWY 33 + 543241N 0053834W -
543224N 0053922W -
543304N 0054002W thence anti-clockwise by the arc of a circle radius 2 NM centred on 543452N 0054131W to
543322N 0053916W -
543241N 0053834W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.642805555599999,54.5446027778,609.6 -5.6543445833,54.556013,609.6 -5.6583959388,54.5541442047,609.6 -5.662720605,54.5524954264,609.6 -5.6672833056,54.5510800833,609.6 -5.656119444400001,54.5400444444,609.6 -5.642805555599999,54.5446027778,609.6 + + + + +
+ + EGRU406A WALNEY + A circle, 2 NM radius, centred at 540752N 0031548W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2632277778,54.1643771067,609.6 -3.2690585169,54.1642005933,609.6 -3.274827301300001,54.1636729286,609.6 -3.280472839,54.1627997191,609.6 -3.285935157,54.1615902424,609.6 -3.291156242,54.1600573477,609.6 -3.2960806603,54.1582173188,609.6 -3.3006561493,54.1560896996,609.6 -3.3048341738,54.1536970853,609.6 -3.3085704421,54.1510648816,609.6 -3.3118253756,54.1482210329,609.6 -3.3145645274,54.1451957247,609.6 -3.3167589447,54.14202106170001,609.6 -3.3183854724,54.1387307264,609.6 -3.319426994,54.1353596202,609.6 -3.3198726078,54.1319434927,609.6 -3.3197177365,54.1285185624,609.6 -3.3189641693,54.125121132,609.6 -3.3176200374,54.1217872042,609.6 -3.3156997208,54.1185520999,609.6 -3.3132236912,54.1154500854,609.6 -3.3102182896,54.1125140096,609.6 -3.306715442999999,54.1097749575,609.6 -3.3027523237,54.1072619224,609.6 -3.2983709527,54.1050015,609.6 -3.2936177545,54.1030176089,609.6 -3.2885430655,54.1013312379,609.6 -3.2832006024,54.0999602261,609.6 -3.277646896399999,54.0989190751,609.6 -3.271940697799999,54.0982187963,609.6 -3.2661423583,54.0978667957,609.6 -3.2603131973,54.0978667957,609.6 -3.254514857799999,54.0982187963,609.6 -3.2488086591,54.0989190751,609.6 -3.2432549531,54.0999602261,609.6 -3.2379124901,54.1013312379,609.6 -3.2328378011,54.1030176089,609.6 -3.2280846029,54.1050015,609.6 -3.2237032319,54.1072619224,609.6 -3.2197401125,54.1097749575,609.6 -3.216237265999999,54.1125140096,609.6 -3.2132318643,54.1154500854,609.6 -3.2107558347,54.1185520999,609.6 -3.2088355182,54.1217872042,609.6 -3.2074913862,54.125121132,609.6 -3.2067378191,54.1285185624,609.6 -3.2065829477,54.1319434927,609.6 -3.2070285615,54.1353596202,609.6 -3.2080700832,54.1387307264,609.6 -3.2096966109,54.14202106170001,609.6 -3.2118910282,54.1451957247,609.6 -3.21463018,54.1482210329,609.6 -3.2178851135,54.1510648816,609.6 -3.221621381799999,54.1536970853,609.6 -3.2257994062,54.1560896996,609.6 -3.230374895200001,54.1582173188,609.6 -3.2352993136,54.1600573477,609.6 -3.2405203986,54.1615902424,609.6 -3.2459827166,54.1627997191,609.6 -3.2516282543,54.1636729286,609.6 -3.257397038600001,54.1642005933,609.6 -3.2632277778,54.1643771067,609.6 + + + + +
+ + EGRU406B WALNEY RWY 17 + 541032N 0031742W -
541040N 0031649W -
540949N 0031628W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to
540939N 0031720W -
541032N 0031742W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.295125,54.1756527778,609.6 -3.2888458333,54.1607845278,609.6 -3.2841622035,54.1620244874,609.6 -3.2793062909,54.1630103456,609.6 -3.2743180556,54.163734,609.6 -3.2802583333,54.17781111109999,609.6 -3.295125,54.1756527778,609.6 + + + + +
+ + EGRU406C WALNEY RWY 35 + 540454N 0031423W -
540447N 0031517W -
540552N 0031544W thence anti-clockwise by the arc of a circle radius 2 NM centred on 540752N 0031548W to
540557N 0031450W -
540454N 0031423W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2398166667,54.08177777780001,609.6 -3.2471365833,54.0991938333,609.6 -3.25211691,54.0984692599,609.6 -3.2571882587,54.0980124281,609.6 -3.2623090833,54.09782708329999,609.6 -3.254649999999999,54.0796194444,609.6 -3.2398166667,54.08177777780001,609.6 + + + + +
+ + EGRU408A LEEMING + A circle, 2.5 NM radius, centred at 541733N 0013207W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5352777778,54.3340952335,609.6 -1.5418450861,54.33391761759999,609.6 -1.548356196,54.3333862896,609.6 -1.5547553941,54.33250579620001,609.6 -1.5609879334,54.3312836713,609.6 -1.567000505,54.3297303713,609.6 -1.572741698,54.3278591848,609.6 -1.5781624417,54.3256861177,609.6 -1.5832164274,54.3232297559,609.6 -1.5878605055,54.3205111044,609.6 -1.5920550547,54.3175534068,609.6 -1.5957643201,54.3143819454,609.6 -1.5989567169,54.3110238238,609.6 -1.6016050982,54.3075077339,609.6 -1.6036869829,54.30386371000001,609.6 -1.6051847444,54.300122871,609.6 -1.6060857555,54.2963171542,609.6 -1.6063824916,54.292479042,609.6 -1.6060725893,54.2886412841,609.6 -1.6051588604,54.28483661849999,609.6 -1.6036492625,54.28109749150001,609.6 -1.6015568259,54.27745578219999,609.6 -1.5988995367,54.2739425307,609.6 -1.595700179,54.2705876747,609.6 -1.5919861371,54.2674197949,609.6 -1.5877891582,54.26446587280001,609.6 -1.5831450801,54.26175106209999,609.6 -1.578093524,54.2592984758,609.6 -1.5726775569,54.2571289903,609.6 -1.5669433247,54.2552610693,609.6 -1.5609396611,54.2537106078,609.6 -1.5547176737,54.2524907976,609.6 -1.5483303119,54.2516120162,609.6 -1.5418319199,54.25108173930001,609.6 -1.5352777778,54.25090447780001,609.6 -1.5287236356,54.25108173930001,609.6 -1.5222252436,54.2516120162,609.6 -1.5158378819,54.2524907976,609.6 -1.5096158945,54.2537106078,609.6 -1.5036122309,54.2552610693,609.6 -1.4978779987,54.2571289903,609.6 -1.4924620315,54.2592984758,609.6 -1.4874104755,54.26175106209999,609.6 -1.4827663974,54.26446587280001,609.6 -1.4785694185,54.2674197949,609.6 -1.4748553766,54.2705876747,609.6 -1.4716560189,54.2739425307,609.6 -1.4689987296,54.27745578219999,609.6 -1.466906293,54.28109749150001,609.6 -1.4653966952,54.28483661849999,609.6 -1.4644829663,54.2886412841,609.6 -1.4641730639,54.292479042,609.6 -1.4644698001,54.2963171542,609.6 -1.4653708112,54.300122871,609.6 -1.4668685726,54.30386371000001,609.6 -1.4689504574,54.3075077339,609.6 -1.4715988386,54.3110238238,609.6 -1.4747912355,54.3143819454,609.6 -1.4785005008,54.3175534068,609.6 -1.4826950501,54.3205111044,609.6 -1.4873391281,54.3232297559,609.6 -1.4923931138,54.3256861177,609.6 -1.4978138575,54.3278591848,609.6 -1.5035550505,54.3297303713,609.6 -1.5095676221,54.3312836713,609.6 -1.5158001614,54.33250579620001,609.6 -1.5221993595,54.3333862896,609.6 -1.5287104694,54.33391761759999,609.6 -1.5352777778,54.3340952335,609.6 + + + + +
+ + EGRU408B LEEMING RWY 16 + 542028N 0013452W -
542041N 0013402W -
541955N 0013327W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541942N 0013417W -
542028N 0013452W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5811833333,54.3410333333,609.6 -1.5713919444,54.32833619439999,609.6 -1.5668795474,54.32976553310001,609.6 -1.5622023345,54.3310008906,609.6 -1.5573846944,54.3320358333,609.6 -1.5671611111,54.3447194444,609.6 -1.5811833333,54.3410333333,609.6 + + + + +
+ + EGRU408C LEEMING RWY 34 + 541438N 0012923W -
541425N 0013013W -
541511N 0013048W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541524N 0012958W -
541438N 0012923W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4897166667,54.24400833329999,609.6 -1.4993772778,54.2566009444,609.6 -1.5038895877,54.25518072439999,609.6 -1.5085646991,54.2539544356,609.6 -1.5133783333,54.2529284167,609.6 -1.5037027778,54.24032222220001,609.6 -1.4897166667,54.24400833329999,609.6 + + + + +
+ + EGRU408D LEEMING RWY 03 + 541517N 0013411W -
541532N 0013459W -
541539N 0013453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541521N 0013407W -
541517N 0013411W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5696216944,54.2546920278,609.6 -1.5686279167,54.2557684444,609.6 -1.5730861296,54.2572780563,609.6 -1.5773459603,54.2589728589,609.6 -1.58138525,54.26084375,609.6 -1.5831166667,54.2589676944,609.6 -1.5696216944,54.2546920278,609.6 + + + + +
+ + EGRU408E LEEMING RWY 21 + 542039N 0013015W -
542024N 0012927W -
541944N 0013003W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 541733N 0013207W to
541957N 0013055W -
542039N 0013015W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5042563056,54.3442184167,609.6 -1.5152062778,54.3324053056,609.6 -1.5103125354,54.3314499726,609.6 -1.505550483,54.3302895303,609.6 -1.5009450833,54.32893033329999,609.6 -1.4907334444,54.3399428056,609.6 -1.5042563056,54.3442184167,609.6 + + + + +
+ + EGRU409A TEESSIDE INTERNATIONAL + A circle, 2.5 NM radius, centred at 543033N 0012546W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4294444444,54.5507603988,609.6 -1.436046508,54.5505827878,609.6 -1.4425920743,54.5500514747,609.6 -1.449025134,54.5491710062,609.6 -1.4552906489,54.547948916,609.6 -1.4613350273,54.5463956606,609.6 -1.4671065851,54.5445245284,609.6 -1.4725559916,54.5423515254,609.6 -1.4776366926,54.539895237,609.6 -1.4823053102,54.5371766681,609.6 -1.4865220138,54.534219062,609.6 -1.4902508599,54.5310477007,609.6 -1.4934600974,54.5276896871,609.6 -1.4961224369,54.5241737127,609.6 -1.4982152799,54.520529811,609.6 -1.4997209079,54.5167891002,609.6 -1.5006266288,54.51298351660001,609.6 -1.5009248799,54.5091455415,609.6 -1.500613287,54.50530792369999,609.6 -1.4996946787,54.5015033997,609.6 -1.4981770565,54.49776441470001,609.6 -1.4960735209,54.4941228462,609.6 -1.4934021546,54.4906097331,609.6 -1.4901858634,54.48725501139999,609.6 -1.4864521771,54.48408726040001,609.6 -1.4822330114,54.48113346020001,609.6 -1.4775643938,54.4784187631,609.6 -1.4724861548,54.4759662806,609.6 -1.4670415886,54.47379688789999,609.6 -1.4612770844,54.4719290476,609.6 -1.4552417328,54.47037865349999,609.6 -1.4489869105,54.4691588966,609.6 -1.442565845,54.4682801539,609.6 -1.4360331662,54.46774990039999,609.6 -1.4294444444,54.4675726466,609.6 -1.4228557227,54.46774990039999,609.6 -1.4163230438,54.4682801539,609.6 -1.4099019784,54.4691588966,609.6 -1.4036471561,54.47037865349999,609.6 -1.3976118045,54.4719290476,609.6 -1.3918473003,54.47379688789999,609.6 -1.3864027341,54.4759662806,609.6 -1.3813244951,54.4784187631,609.6 -1.3766558775,54.48113346020001,609.6 -1.3724367118,54.48408726040001,609.6 -1.3687030255,54.48725501139999,609.6 -1.3654867343,54.4906097331,609.6 -1.362815368,54.4941228462,609.6 -1.3607118324,54.49776441470001,609.6 -1.3591942102,54.5015033997,609.6 -1.3582756019,54.50530792369999,609.6 -1.357964009,54.5091455415,609.6 -1.3582622601,54.51298351660001,609.6 -1.359167981,54.5167891002,609.6 -1.360673609,54.520529811,609.6 -1.362766452,54.5241737127,609.6 -1.3654287915,54.5276896871,609.6 -1.368638029,54.5310477007,609.6 -1.3723668751,54.534219062,609.6 -1.3765835787,54.5371766681,609.6 -1.3812521963,54.539895237,609.6 -1.3863328973,54.5423515254,609.6 -1.3917823038,54.5445245284,609.6 -1.3975538616,54.5463956606,609.6 -1.40359824,54.547948916,609.6 -1.4098637549,54.5491710062,609.6 -1.4162968146,54.5500514747,609.6 -1.4228423809,54.5505827878,609.6 -1.4294444444,54.5507603988,609.6 + + + + +
+ + EGRU409B TEESSIDE INTERNATIONAL RWY 05 + 542807N 0012938W -
542831N 0013016W -
542904N 0012913W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to
542840N 0012836W -
542807N 0012938W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4940166667,54.468525,609.6 -1.4765378333,54.47788497219999,609.6 -1.4802882836,54.4799412982,609.6 -1.4837748599,54.48214957159999,609.6 -1.4869794167,54.48449833330001,609.6 -1.5044444444,54.4751444444,609.6 -1.4940166667,54.468525,609.6 + + + + +
+ + EGRU409C TEESSIDE INTERNATIONAL RWY 23 + 543259N 0012153W -
543235N 0012115W -
543202N 0012219W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 543033N 0012546W to
543226N 0012256W -
543259N 0012153W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3646916667,54.54980277779999,609.6 -1.3822803611,54.5404305,609.6 -1.3785290961,54.53837112879999,609.6 -1.3750432165,54.5361598086,609.6 -1.3718408611,54.5338080556,609.6 -1.3542388889,54.5431861111,609.6 -1.3646916667,54.54980277779999,609.6 + + + + +
+ + EGRU410A TOPCLIFFE + A circle, 2 NM radius, centred at 541220N 0012254W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3816277778,54.2389044702,609.6 -1.3874690187,54.23872795859999,609.6 -1.3932481928,54.2382002993,609.6 -1.3989038975,54.23732709879999,609.6 -1.4043760513,54.2361176346,609.6 -1.4096065363,54.23458475609999,609.6 -1.4145398186,54.2327447467,609.6 -1.4191235415,54.2306171503,609.6 -1.4233090821,54.2282245621,609.6 -1.4270520693,54.2255923874,609.6 -1.4303128533,54.2227485706,609.6 -1.4330569254,54.2197232969,609.6 -1.4352552811,54.21654867090001,609.6 -1.4368847239,54.2132583746,609.6 -1.4379281072,54.209887309,609.6 -1.4383745099,54.2064712235,609.6 -1.4382193472,54.20304633599999,609.6 -1.437464412,54.1996489489,609.6 -1.4361178506,54.1963150643,609.6 -1.4341940696,54.1930800027,609.6 -1.4317135777,54.18997802970001,609.6 -1.4287027635,54.1870419937,609.6 -1.4251936121,54.1843029793,609.6 -1.4212233625,54.1817899792,609.6 -1.4168341115,54.17952958880001,609.6 -1.4120723669,54.17754572590001,609.6 -1.4069885556,54.1758593791,609.6 -1.4016364907,54.1744883872,609.6 -1.3960728045,54.1734472513,609.6 -1.3903563526,54.1727469828,609.6 -1.3845475949,54.1723949873,609.6 -1.3787079606,54.1723949873,609.6 -1.372899203,54.1727469828,609.6 -1.3671827511,54.1734472513,609.6 -1.3616190649,54.1744883872,609.6 -1.356267,54.1758593791,609.6 -1.3511831886,54.17754572590001,609.6 -1.3464214441,54.17952958880001,609.6 -1.342032193,54.1817899792,609.6 -1.3380619434,54.1843029793,609.6 -1.334552792,54.1870419937,609.6 -1.3315419779,54.18997802970001,609.6 -1.329061486,54.1930800027,609.6 -1.3271377049,54.1963150643,609.6 -1.3257911435,54.1996489489,609.6 -1.3250362084,54.20304633599999,609.6 -1.3248810456,54.2064712235,609.6 -1.3253274484,54.209887309,609.6 -1.3263708316,54.2132583746,609.6 -1.3280002745,54.21654867090001,609.6 -1.3301986301,54.2197232969,609.6 -1.3329427022,54.2227485706,609.6 -1.3362034863,54.2255923874,609.6 -1.3399464734,54.2282245621,609.6 -1.3441320141,54.2306171503,609.6 -1.3487157369,54.2327447467,609.6 -1.3536490193,54.23458475609999,609.6 -1.3588795043,54.2361176346,609.6 -1.3643516581,54.23732709879999,609.6 -1.3700073628,54.2382002993,609.6 -1.3757865369,54.23872795859999,609.6 -1.3816277778,54.2389044702,609.6 + + + + +
+ + EGRU410B TOPCLIFFE RWY 02 + 540928N 0012421W -
540940N 0012512W -
541036N 0012434W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541024N 0012343W -
540928N 0012421W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.40583975,54.1578682778,609.6 -1.3953372778,54.1733367778,609.6 -1.4002433356,54.1741926445,609.6 -1.4049981522,54.1753043042,609.6 -1.4095630833,54.1766627222,609.6 -1.4200591667,54.16119580559999,609.6 -1.40583975,54.1578682778,609.6 + + + + +
+ + EGRU410C TOPCLIFFE RWY 20 + 541524N 0012119W -
541512N 0012027W -
541405N 0012113W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541417N 0012204W -
541524N 0012119W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3551701389,54.25661588889999,609.6 -1.3679102222,54.2379189722,609.6 -1.3629969339,54.23706249489999,609.6 -1.3582356996,54.23594986559999,609.6 -1.3536653611,54.2345901667,609.6 -1.3409179167,54.2532884167,609.6 -1.3551701389,54.25661588889999,609.6 + + + + +
+ + EGRU410D TOPCLIFFE RWY 13 + 541355N 0012720W -
541421N 0012647W -
541344N 0012520W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541318N 0012553W -
541355N 0012720W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4554805,54.2318486944,609.6 -1.4313874444,54.2216514722,609.6 -1.428721035,54.2242160026,609.6 -1.4256705754,54.2266291543,609.6 -1.4222608889,54.22887125,609.6 -1.4464896111,54.2391268611,609.6 -1.4554805,54.2318486944,609.6 + + + + +
+ + EGRU410E TOPCLIFFE RWY 31 + 541053N 0011838W -
541027N 0011910W -
541059N 0012024W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541125N 0011953W -
541053N 0011838W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3105919444,54.18147461109999,609.6 -1.3312787778,54.1902709444,609.6 -1.3338459199,54.18767256549999,609.6 -1.3368016981,54.185220428,609.6 -1.340122,54.1829344722,609.6 -1.3195703333,54.1741963889,609.6 -1.3105919444,54.18147461109999,609.6 + + + + +
+ + EGRU410F TOPCLIFFE RWY 07 + 541107N 0012746W -
541138N 0012800W -
541155N 0012614W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541124N 0012555W -
541107N 0012746W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.4628026944,54.1851534167,609.6 -1.4318126944,54.1900875,609.6 -1.4340062649,54.1928130821,609.6 -1.4357705656,54.1956438446,609.6 -1.4370910556,54.1985565833,609.6 -1.4668027778,54.1938257778,609.6 -1.4628026944,54.1851534167,609.6 + + + + +
+ + EGRU410G TOPCLIFFE RWY 25 + 541311N 0011812W -
541240N 0011758W -
541225N 0011930W thence anti-clockwise by the arc of a circle radius 2 NM centred on 541220N 0012254W to
541257N 0011939W -
541311N 0011812W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3034665833,54.2197288889,609.6 -1.3276355556,54.21591200000001,609.6 -1.3262713683,54.2130061059,609.6 -1.3253615157,54.2100397783,609.6 -1.3249133611,54.2070373611,609.6 -1.299464,54.2110565833,609.6 -1.3034665833,54.2197288889,609.6 + + + + +
+ + EGRU411A ISLE OF MAN + A circle, 2.7 NM radius, centred at 540500N 0043724W
Upper limit: UNL
Lower limit: SFC
Class: Restricted airspace active H24. Small unmanned aircraft flight not permitted except with the permission of the Isle of Man CAA. Contact caa@gov.im or 01624-682358]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6233333333,54.1282577424,30449.52 -4.6300934172,54.12808175609999,30449.52 -4.6368004237,54.1275551791,30449.52 -4.6434016959,54.1266821455,30449.52 -4.6498454151,54.12546950960001,30449.52 -4.6560810113,54.1239267908,30449.52 -4.6620595627,54.1220660988,30449.52 -4.667734183,54.1199020374,30449.52 -4.6730603909,54.117451589,30449.52 -4.6779964608,54.11473398009999,30449.52 -4.6825037501,54.1117705296,30449.52 -4.6865470027,54.10858448009999,30449.52 -4.6900946234,54.1052008146,30449.52 -4.6931189245,54.1016460595,30449.52 -4.6955963394,54.0979480755,30449.52 -4.6975076042,54.09413583830001,30449.52 -4.6988379044,54.09023921090001,30449.52 -4.6995769864,54.0862887089,30449.52 -4.6997192325,54.0823152611,30449.52 -4.6992637003,54.0783499674,30449.52 -4.6982141239,54.0744238547,30449.52 -4.6965788803,54.0705676349,30449.52 -4.694370918,54.0668114647,30449.52 -4.6916076513,54.06318471040001,30449.52 -4.6883108199,54.0597157192,30449.52 -4.6845063152,54.05643159820001,30449.52 -4.6802239747,54.0533580037,30449.52 -4.675497347,54.050518942,30449.52 -4.6703634275,54.0479365828,30449.52 -4.6648623697,54.0456310874,30449.52 -4.6590371708,54.0436204524,30449.52 -4.6529333379,54.0419203703,30449.52 -4.6465985335,54.04054410820001,30449.52 -4.6400822067,54.0395024049,30449.52 -4.6334352097,54.0388033878,30449.52 -4.6267094045,54.0384525106,30449.52 -4.6199572621,54.0384525106,30449.52 -4.613231457,54.0388033878,30449.52 -4.60658446,54.0395024049,30449.52 -4.6000681332,54.04054410820001,30449.52 -4.5937333288,54.0419203703,30449.52 -4.5876294958,54.0436204524,30449.52 -4.581804297,54.0456310874,30449.52 -4.5763032391,54.0479365828,30449.52 -4.5711693197,54.050518942,30449.52 -4.5664426919,54.0533580037,30449.52 -4.5621603515,54.05643159820001,30449.52 -4.5583558468,54.0597157192,30449.52 -4.5550590154,54.06318471040001,30449.52 -4.5522957487,54.0668114647,30449.52 -4.5500877864,54.0705676349,30449.52 -4.5484525427,54.0744238547,30449.52 -4.5474029664,54.0783499674,30449.52 -4.5469474342,54.0823152611,30449.52 -4.5470896803,54.0862887089,30449.52 -4.5478287623,54.09023921090001,30449.52 -4.5491590625,54.09413583830001,30449.52 -4.5510703273,54.0979480755,30449.52 -4.5535477422,54.1016460595,30449.52 -4.5565720433,54.1052008146,30449.52 -4.560119664,54.10858448009999,30449.52 -4.5641629166,54.1117705296,30449.52 -4.5686702059,54.11473398009999,30449.52 -4.5736062758,54.117451589,30449.52 -4.5789324837,54.1199020374,30449.52 -4.584607104,54.1220660988,30449.52 -4.5905856554,54.1239267908,30449.52 -4.5968212515,54.12546950960001,30449.52 -4.6032649708,54.1266821455,30449.52 -4.609866243,54.1275551791,30449.52 -4.6165732494,54.12808175609999,30449.52 -4.6233333333,54.1282577424,30449.52 + + + + +
+ + EGRU412 ISLE OF MAN PRISON + 542124N 0043154W -
542128N 0043151W -
542129N 0043150W -
542133N 0043143W -
542132N 0043141W -
542117N 0043127W -
542114N 0043143W -
542113N 0043153W -
542116N 0043201W -
542117N 0043201W -
542124N 0043154W
Upper limit: UNL
Lower limit: SFC
Class: Restricted airspace active H24. Contact caa@gov.im or 01624-682358 for further details]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5316583333,54.3567583333,30449.52 -4.5337277778,54.3548138889,30449.52 -4.5336166667,54.3545555556,30449.52 -4.5313527778,54.35362499999999,30449.52 -4.5287194444,54.35375555560001,30449.52 -4.5241055556,54.3547611111,30449.52 -4.5280277778,54.3588777778,30449.52 -4.5287472222,54.35928333330001,30449.52 -4.5304888889,54.35806111109999,30449.52 -4.5308222222,54.3577472222,30449.52 -4.5316583333,54.3567583333,30449.52 + + + + +
+ + EGRU413 HMP DEERBOLT + 543255N 0015600W -
543222N 0015541W -
543214N 0015609W -
543221N 0015700W -
543244N 0015701W -
543255N 0015600W
Upper limit: 1100 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 602 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.9334416667,54.5484861111,335.28 -1.9503194444,54.54561666669999,335.28 -1.9500527778,54.5391583333,335.28 -1.9359555556,54.5372027778,335.28 -1.9281472222,54.53937777779999,335.28 -1.9334416667,54.5484861111,335.28 + + + + +
+ + EGRU414 HMP DURHAM + 544641N 0013402W -
544635N 0013340W -
544614N 0013337W -
544602N 0013352W -
544609N 0013429W -
544637N 0013440W -
544641N 0013402W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 196 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5670861111,54.7781138889,182.88 -1.5776388889,54.7768805556,182.88 -1.5746444444,54.7692666667,182.88 -1.5645666667,54.7673194444,182.88 -1.5601888889,54.7706861111,182.88 -1.5609722222,54.77634722219999,182.88 -1.5670861111,54.7781138889,182.88 + + + + +
+ + EGRU415 HMP FRANKLAND/LOW NEWTON + 544839N 0013233W -
544800N 0013221W -
544753N 0013317W -
544810N 0013351W -
544832N 0013351W -
544839N 0013233W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 208 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.5424833333,54.81091944439999,213.36 -1.5641277778,54.8088,213.36 -1.564175,54.8027777778,213.36 -1.5547861111,54.7981777778,213.36 -1.5392111111,54.8001333333,213.36 -1.5424833333,54.81091944439999,213.36 + + + + +
+ + EGRU416 HMP HOLME HOUSE + 543500N 0011748W -
543500N 0011715W -
543433N 0011658W -
543422N 0011718W -
543423N 0011748W -
543435N 0011809W -
543448N 0011809W -
543500N 0011748W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 39 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2967611111,54.5833138889,152.4 -1.302475,54.5800361111,152.4 -1.3024944444,54.5763805556,152.4 -1.2966055556,54.57292222219999,152.4 -1.2882555556,54.5729055556,152.4 -1.2827388889,54.57594722220001,152.4 -1.2874805556,54.58325,152.4 -1.2967611111,54.5833138889,152.4 + + + + +
+ + EGRU417 HMP LANCASTER FARMS + 540337N 0024623W -
540334N 0024557W -
540325N 0024544W -
540304N 0024548W -
540255N 0024607W -
540256N 0024629W -
540309N 0024645W -
540329N 0024641W -
540337N 0024623W
Upper limit: 700 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 238 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7730277778,54.0601888889,213.36 -2.7780666667,54.058,213.36 -2.7792722222,54.0525166667,213.36 -2.7747222222,54.0490194444,213.36 -2.7687166667,54.0486583333,213.36 -2.7634277778,54.0510416667,213.36 -2.7621972222,54.0569194444,213.36 -2.7657555556,54.0595777778,213.36 -2.7730277778,54.0601888889,213.36 + + + + +
+ + EGRU501A LONDONDERRY/EGLINTON + A circle, 2.5 NM radius, centred at 550234N 0070943W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.1619444444,55.084367829,609.6 -7.16863411,55.0841902302,609.6 -7.1752665251,55.08365895349999,609.6 -7.1817849341,55.0827785455,609.6 -7.1881335654,55.08155654,609.6 -7.1942581135,55.0800033933,609.6 -7.2001062067,55.0781323936,609.6 -7.205627858,55.0759595465,609.6 -7.2107758951,55.0735034372,609.6 -7.2155063643,55.07078507,609.6 -7.219778907500001,55.0678276874,609.6 -7.2235571058,55.06465657050001,609.6 -7.2268087892,55.0612988211,609.6 -7.2295063091,55.0577831292,609.6 -7.2316267707,55.05413952659999,609.6 -7.2331522246,55.0503991296,609.6 -7.234069814599999,55.0465938723,609.6 -7.2343718823,55.0427562335,609.6 -7.2340560266,55.038918959,609.6 -7.233125118200001,55.0351147825,609.6 -7.2315872689,55.0313761459,609.6 -7.229455757,55.0277349233,609.6 -7.2267489084,55.0242221499,609.6 -7.2234899355,55.0208677583,609.6 -7.2197067351,55.0177003241,609.6 -7.215431647400001,55.0147468236,609.6 -7.210701178200001,55.0120324057,609.6 -7.2055556855,55.00958017850001,609.6 -7.2000390363,55.00741101410001,609.6 -7.1941982326,55.0055433721,609.6 -7.188083013200001,55.00399314400001,609.6 -7.1817454321,55.0027735185,609.6 -7.1752394186,55.0018948709,609.6 -7.1686203219,55.001364675,609.6 -7.1619444444,55.00118744049999,609.6 -7.1552685669,55.001364675,609.6 -7.1486494703,55.0018948709,609.6 -7.1421434567,55.0027735185,609.6 -7.135805875599999,55.00399314400001,609.6 -7.1296906563,55.0055433721,609.6 -7.1238498526,55.00741101410001,609.6 -7.118333203400001,55.00958017850001,609.6 -7.1131877107,55.0120324057,609.6 -7.108457241399999,55.0147468236,609.6 -7.1041821538,55.0177003241,609.6 -7.1003989534,55.0208677583,609.6 -7.0971399805,55.0242221499,609.6 -7.0944331319,55.0277349233,609.6 -7.09230162,55.0313761459,609.6 -7.090763770699999,55.0351147825,609.6 -7.0898328623,55.038918959,609.6 -7.0895170066,55.0427562335,609.6 -7.089819074300001,55.0465938723,609.6 -7.0907366643,55.0503991296,609.6 -7.0922621182,55.05413952659999,609.6 -7.0943825798,55.0577831292,609.6 -7.0970800997,55.0612988211,609.6 -7.1003317831,55.06465657050001,609.6 -7.104109981399999,55.0678276874,609.6 -7.1083825246,55.07078507,609.6 -7.1131129938,55.0735034372,609.6 -7.1182610309,55.0759595465,609.6 -7.1237826822,55.0781323936,609.6 -7.1296307754,55.0800033933,609.6 -7.1357553235,55.08155654,609.6 -7.1421039548,55.0827785455,609.6 -7.1486223637,55.08365895349999,609.6 -7.1552547789,55.0841902302,609.6 -7.1619444444,55.084367829,609.6 + + + + +
+ + EGRU501B LONDONDERRY/EGLINTON RWY 08 + 550123N 0071453W -
550154N 0071509W -
550206N 0071359W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to
550135N 0071343W -
550123N 0071453W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.2479777778,55.0229694444,609.6 -7.2284896389,55.02637775,609.6 -7.2303766768,55.02917460599999,609.6 -7.2319081121,55.0320422966,609.6 -7.233075916700001,55.0349659167,609.6 -7.2525111111,55.0315666667,609.6 -7.2479777778,55.0229694444,609.6 + + + + +
+ + EGRU501C LONDONDERRY/EGLINTON RWY 26 + 550345N 0070429W -
550314N 0070412W -
550301N 0070527W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550234N 0070943W to
550332N 0070543W -
550345N 0070429W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.074627777799999,55.06254166670001,609.6 -7.0952194167,55.0589717778,609.6 -7.0933618418,55.05616776699999,609.6 -7.091861437,55.0532941684,609.6 -7.090725944399999,55.05036594439999,609.6 -7.070083333300001,55.0539444444,609.6 -7.074627777799999,55.06254166670001,609.6 + + + + +
+ + EGRU502A ISLAY + A circle, 2 NM radius, centred at 554100N 0061535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.259722222200001,55.7166018889,609.6 -6.265781982300001,55.71642541239999,609.6 -6.271777344999999,55.7158978586,609.6 -6.2776446024,55.7150248334,609.6 -6.2833214183,55.71381561379999,609.6 -6.288747494299999,55.712283048,609.6 -6.2938652149,55.7104434183,609.6 -6.298620262100001,55.70831626660001,609.6 -6.3029621938,55.705924186,609.6 -6.3068449806,55.7032925788,609.6 -6.3102274936,55.70044938560001,609.6 -6.313073939,55.6974247876,609.6 -6.315354235199999,55.6942508839,609.6 -6.317044327400001,55.69096135070001,609.6 -6.318126438,55.6875910823,609.6 -6.3185892489,55.68417582049999,609.6 -6.318428015199999,55.68075177480001,609.6 -6.3176446087,55.6773552385,609.6 -6.316247491,55.674022204,609.6 -6.3142516173,55.6707879818,609.6 -6.311678271700001,55.6676868271,609.6 -6.3085548363,55.6647515777,609.6 -6.3049144963,55.66201330769999,609.6 -6.3007958855,55.6595009996,609.6 -6.296242674400001,55.6572412388,609.6 -6.291303106999999,55.65525793430001,609.6 -6.2860294903,55.65357206640001,609.6 -6.2804776422,55.6522014666,609.6 -6.2747063031,55.65116063029999,609.6 -6.2687765182,55.65046056400001,609.6 -6.2627509957,55.6501086704,609.6 -6.2566934487,55.6501086704,609.6 -6.2506679263,55.65046056400001,609.6 -6.2447381414,55.65116063029999,609.6 -6.2389668023,55.6522014666,609.6 -6.2334149541,55.65357206640001,609.6 -6.228141337499999,55.65525793430001,609.6 -6.22320177,55.6572412388,609.6 -6.2186485589,55.6595009996,609.6 -6.2145299481,55.66201330769999,609.6 -6.2108896082,55.6647515777,609.6 -6.2077661728,55.6676868271,609.6 -6.2051928272,55.6707879818,609.6 -6.2031969535,55.674022204,609.6 -6.201799835800001,55.6773552385,609.6 -6.201016429199999,55.68075177480001,609.6 -6.200855195599999,55.68417582049999,609.6 -6.201318006500001,55.6875910823,609.6 -6.202400117000001,55.69096135070001,609.6 -6.204090209199999,55.6942508839,609.6 -6.2063705054,55.6974247876,609.6 -6.2092169508,55.70044938560001,609.6 -6.212599463800001,55.7032925788,609.6 -6.216482250700001,55.705924186,609.6 -6.2208241824,55.70831626660001,609.6 -6.2255792295,55.7104434183,609.6 -6.2306969501,55.712283048,609.6 -6.2361230262,55.71381561379999,609.6 -6.241799842,55.7150248334,609.6 -6.247667099499999,55.7158978586,609.6 -6.2536624622,55.71642541239999,609.6 -6.259722222200001,55.7166018889,609.6 + + + + +
+ + EGRU502B ISLAY RWY 07 + 553948N 0061952W -
554018N 0062011W -
554032N 0061901W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554002N 0061840W -
553948N 0061952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3310583333,55.66321111109999,609.6 -6.3112065278,55.6671968889,609.6 -6.3135733497,55.6698858046,609.6 -6.3155017861,55.6726843614,609.6 -6.316976027799999,55.6755697778,609.6 -6.3363611111,55.6716777778,609.6 -6.3310583333,55.66321111109999,609.6 + + + + +
+ + EGRU502C ISLAY RWY 25 + 554212N 0061040W -
554142N 0061021W -
554121N 0061206W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554152N 0061224W -
554212N 0061040W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.1778694444,55.70338611110001,609.6 -6.20656975,55.69766322220001,609.6 -6.2045004609,55.6948971441,609.6 -6.202881467100001,55.6920369256,609.6 -6.2017258611,55.6891058889,609.6 -6.1725583333,55.6949222222,609.6 -6.1778694444,55.70338611110001,609.6 + + + + +
+ + EGRU502D ISLAY RWY 12 + 554220N 0062026W -
554248N 0061957W -
554215N 0061820W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554147N 0061850W -
554220N 0062026W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3406861111,55.7055111111,609.6 -6.3138358611,55.69646419439999,609.6 -6.3115212547,55.69916690559999,609.6 -6.3087842929,55.7017407062,609.6 -6.3056472222,55.7041646111,609.6 -6.3325194444,55.7132194444,609.6 -6.3406861111,55.7055111111,609.6 + + + + +
+ + EGRU502E ISLAY RWY 30 + 553941N 0061044W -
553913N 0061113W -
553945N 0061249W thence anti-clockwise by the arc of a circle radius 2 NM centred on 554100N 0061535W to
554013N 0061220W -
553941N 0061044W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.1788166667,55.6612916667,609.6 -6.2055239444,55.6703383333,609.6 -6.2078192916,55.66763068100001,609.6 -6.210536853499999,55.66505095510001,609.6 -6.2136544444,55.6626201389,609.6 -6.186966666699999,55.6535805556,609.6 -6.1788166667,55.6612916667,609.6 + + + + +
+ + EGRU503A CAMPBELTOWN + A circle, 2 NM radius, centred at 552615N 0054117W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.6881,55.4708865645,609.6 -5.6941220147,55.4707100823,609.6 -5.7000800346,55.4701825112,609.6 -5.705910750200001,55.46930945730001,609.6 -5.711552214399999,55.4681001977,609.6 -5.716944505800001,55.4665675807,609.6 -5.7220303684,55.4647278888,609.6 -5.7267558229,55.46260066430001,609.6 -5.7310707415,55.46020850039999,609.6 -5.7349293813,55.4575768001,609.6 -5.7382908687,55.4547335046,609.6 -5.7411196321,55.4517087954,609.6 -5.743385775599999,55.44853477299999,609.6 -5.745065392900001,55.4452451142,609.6 -5.7461408152,55.4418747144,609.6 -5.746600793000001,55.4384593168,609.6 -5.746440609,55.43503513219999,609.6 -5.7456621213,55.4316384554,609.6 -5.744273737,55.4283052805,609.6 -5.7422903165,55.4250709195,609.6 -5.73973301,55.4219696294,609.6 -5.7366290279,55.4190342499,609.6 -5.733011348100001,55.4162958566,609.6 -5.728918363500001,55.4137834338,609.6 -5.7243934726,55.41152356869999,609.6 -5.719484619799999,55.4095401715,609.6 -5.714243787199999,55.4078542242,609.6 -5.7087264464,55.4064835594,609.6 -5.7029909739,55.40544267330001,609.6 -5.6970980365,55.4047425735,609.6 -5.6911099543,55.404390663,609.6 -5.6850900457,55.404390663,609.6 -5.6791019635,55.4047425735,609.6 -5.673209026100001,55.40544267330001,609.6 -5.6674735536,55.4064835594,609.6 -5.661956212799999,55.4078542242,609.6 -5.656715380200001,55.4095401715,609.6 -5.6518065274,55.41152356869999,609.6 -5.647281636499999,55.4137834338,609.6 -5.643188651899999,55.4162958566,609.6 -5.6395709721,55.4190342499,609.6 -5.63646699,55.4219696294,609.6 -5.633909683500001,55.4250709195,609.6 -5.631926263,55.4283052805,609.6 -5.6305378787,55.4316384554,609.6 -5.629759391,55.43503513219999,609.6 -5.629599206999999,55.4384593168,609.6 -5.6300591848,55.4418747144,609.6 -5.631134607099999,55.4452451142,609.6 -5.632814224400001,55.44853477299999,609.6 -5.6350803679,55.4517087954,609.6 -5.6379091313,55.4547335046,609.6 -5.6412706187,55.4575768001,609.6 -5.6451292585,55.46020850039999,609.6 -5.6494441771,55.46260066430001,609.6 -5.6541696316,55.4647278888,609.6 -5.6592554942,55.4665675807,609.6 -5.664647785599999,55.4681001977,609.6 -5.6702892498,55.46930945730001,609.6 -5.6761199654,55.4701825112,609.6 -5.6820779853,55.4707100823,609.6 -5.6881,55.4708865645,609.6 + + + + +
+ + EGRU503B CAMPBELTOWN RWY 11 + 552646N 0054608W -
552717N 0054552W -
552704N 0054430W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to
552633N 0054446W -
552646N 0054608W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.7688818889,55.4461494167,609.6 -5.74600975,55.4424185278,609.6 -5.745014558799999,55.4453669439,609.6 -5.7435556738,55.4482523464,609.6 -5.7416448611,55.4510512222,609.6 -5.764505805600001,55.4547803611,609.6 -5.7688818889,55.4461494167,609.6 + + + + +
+ + EGRU503C CAMPBELTOWN RWY 29 + 552535N 0053529W -
552504N 0053544W -
552527N 0053804W thence anti-clockwise by the arc of a circle radius 2 NM centred on 552615N 0054117W to
552558N 0053749W -
552535N 0053529W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.5912708611,55.4263978889,609.6 -5.630200833300001,55.4328010278,609.6 -5.631202123399999,55.4298533037,609.6 -5.6326664256,55.42696888670001,609.6 -5.634581749999999,55.42417125000001,609.6 -5.5956437778,55.4177668889,609.6 -5.5912708611,55.4263978889,609.6 + + + + +
+ + EGRU504A PRESTWICK + A circle, 2.5 NM radius, centred at 553034N 0043540W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5945805556,55.5509785198,609.6 -4.6013492444,55.55080093139999,609.6 -4.6080600036,55.550269686,609.6 -4.6146554036,55.54938933010001,609.6 -4.6210790116,55.5481673976,609.6 -4.6272758781,55.54661434449999,609.6 -4.6331930109,55.5447434589,609.6 -4.6387798314,55.5425707464,609.6 -4.6439886091,55.5401147917,609.6 -4.6487748714,55.5373965986,609.6 -4.6530977841,55.5344394092,609.6 -4.6569204995,55.5312685036,609.6 -4.6602104698,55.5279109828,609.6 -4.6629397226,55.5243955356,609.6 -4.6650850957,55.5207521923,609.6 -4.6666284315,55.51701206749999,609.6 -4.6675567258,55.5132070933,609.6 -4.6678622339,55.5093697465,609.6 -4.6675425307,55.50553277060001,609.6 -4.6666005248,55.50172889629999,609.6 -4.6650444277,55.4979905628,609.6 -4.6628876781,55.49434964139999,609.6 -4.6601488213,55.4908371641,609.6 -4.6568513462,55.4874830602,609.6 -4.6530234809,55.48431590209999,609.6 -4.6486979487,55.4813626631,609.6 -4.6439116863,55.4786484888,609.6 -4.6387055281,55.47619648450001,609.6 -4.6331238575,55.4740275195,609.6 -4.6272142294,55.4721600508,609.6 -4.621026967,55.47060996769999,609.6 -4.6146147355,55.469390457,609.6 -4.6080320968,55.4685118925,609.6 -4.6013350494,55.4679817469,609.6 -4.5945805556,55.4678045293,609.6 -4.5878260617,55.4679817469,609.6 -4.5811290143,55.4685118925,609.6 -4.5745463757,55.469390457,609.6 -4.5681341441,55.47060996769999,609.6 -4.5619468817,55.4721600508,609.6 -4.5560372536,55.4740275195,609.6 -4.550455583,55.47619648450001,609.6 -4.5452494248,55.4786484888,609.6 -4.5404631624,55.4813626631,609.6 -4.5361376302,55.48431590209999,609.6 -4.5323097649,55.4874830602,609.6 -4.5290122898,55.4908371641,609.6 -4.526273433,55.49434964139999,609.6 -4.5241166834,55.4979905628,609.6 -4.5225605863,55.50172889629999,609.6 -4.5216185804,55.50553277060001,609.6 -4.5212988772,55.5093697465,609.6 -4.5216043854,55.5132070933,609.6 -4.5225326796,55.51701206749999,609.6 -4.5240760154,55.5207521923,609.6 -4.5262213885,55.5243955356,609.6 -4.5289506413,55.5279109828,609.6 -4.5322406116,55.5312685036,609.6 -4.536063327,55.5344394092,609.6 -4.5403862397,55.5373965986,609.6 -4.545172502,55.5401147917,609.6 -4.5503812797,55.5425707464,609.6 -4.5559681002,55.5447434589,609.6 -4.561885233,55.54661434449999,609.6 -4.5680820995,55.5481673976,609.6 -4.5745057075,55.54938933010001,609.6 -4.5811011075,55.550269686,609.6 -4.5878118667,55.55080093139999,609.6 -4.5945805556,55.5509785198,609.6 + + + + +
+ + EGRU504B PRESTWICK RWY 02 + 552644N 0043643W -
552657N 0043735W -
552808N 0043640W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
552804N 0043541W -
552644N 0043643W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6119638889,55.44545555559999,609.6 -4.5946817778,55.4678045556,609.6 -4.6002036153,55.467927257,609.6 -4.605693511,55.4682859911,609.6 -4.6111202778,55.46887872220001,609.6 -4.6264277778,55.4490722222,609.6 -4.6119638889,55.44545555559999,609.6 + + + + +
+ + EGRU504C PRESTWICK RWY 20 + 553247N 0043304W -
553234N 0043212W -
553215N 0043226W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
553237N 0043311W -
553247N 0043304W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.551125,55.5462972222,609.6 -4.5531429722,55.5436986389,609.6 -4.548697861,55.5418268629,609.6 -4.5445148706,55.539770143,609.6 -4.5406178611,55.5375402222,609.6 -4.5366222222,55.5426833333,609.6 -4.551125,55.5462972222,609.6 + + + + +
+ + EGRU504D PRESTWICK RWY 12 + 553205N 0044100W -
553233N 0044030W -
553205N 0043910W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
553137N 0043939W -
553205N 0044100W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.6832444444,55.534725,609.6 -4.6609490833,55.5270424444,609.6 -4.6585352738,55.5297116791,609.6 -4.655788149,55.5322752062,609.6 -4.6527219722,55.5347196667,609.6 -4.675,55.5423972222,609.6 -4.6832444444,55.534725,609.6 + + + + +
+ + EGRU504E PRESTWICK RWY 30 + 552858N 0043010W -
552831N 0043040W -
552903N 0043211W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 553034N 0043540W to
552930N 0043142W -
552858N 0043010W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5027611111,55.4828555556,609.6 -4.528274,55.4917018333,609.6 -4.5306940537,55.48903589719999,609.6 -4.5334458761,55.4864758646,609.6 -4.5365151111,55.4840350278,609.6 -4.5109833333,55.4751833333,609.6 -4.5027611111,55.4828555556,609.6 + + + + +
+ + EGRU505A GLASGOW + A circle, 2.5 NM radius, centred at 555218N 0042601W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.4336611111,55.9133066058,609.6 -4.4404927814,55.9131290254,609.6 -4.4472659805,55.9125978039,609.6 -4.4539227421,55.911717488,609.6 -4.4604061061,55.9104956113,609.6 -4.4666606098,55.90894262999999,609.6 -4.4726327666,55.907071832,609.6 -4.4782715259,55.9048992227,609.6 -4.4835287129,55.90244338659999,609.6 -4.4883594411,55.8997253273,609.6 -4.4927224969,55.8967682863,609.6 -4.4965806909,55.8935975433,609.6 -4.4999011742,55.8902401984,609.6 -4.5026557162,55.88672493950001,609.6 -4.5048209421,55.883081796,609.6 -4.5063785279,55.8793418811,609.6 -4.5073153518,55.8755371254,609.6 -4.5076236004,55.8717000041,609.6 -4.5073008292,55.8678632586,609.6 -4.5063499773,55.8640596179,609.6 -4.5047793358,55.86032151889999,609.6 -4.502602471,55.8566808305,609.6 -4.4998381033,55.8531685823,609.6 -4.496509942,55.8498147012,609.6 -4.4926464793,55.846647757,609.6 -4.4882807436,55.8436947207,609.6 -4.4834500153,55.8409807353,609.6 -4.4781955083,55.8385289038,609.6 -4.4725620176,55.8363600934,609.6 -4.4665975388,55.83449275910001,609.6 -4.4603528607,55.8329427885,609.6 -4.4538811356,55.8317233669,609.6 -4.4472374298,55.83084486689999,609.6 -4.4404782588,55.8303147604,609.6 -4.4336611111,55.83013755579999,609.6 -4.4268439634,55.8303147604,609.6 -4.4200847924,55.83084486689999,609.6 -4.4134410866,55.8317233669,609.6 -4.4069693615,55.8329427885,609.6 -4.4007246835,55.83449275910001,609.6 -4.3947602046,55.8363600934,609.6 -4.3891267139,55.8385289038,609.6 -4.3838722069,55.8409807353,609.6 -4.3790414787,55.8436947207,609.6 -4.3746757429,55.846647757,609.6 -4.3708122802,55.8498147012,609.6 -4.367484119,55.8531685823,609.6 -4.3647197512,55.8566808305,609.6 -4.3625428864,55.86032151889999,609.6 -4.3609722449,55.8640596179,609.6 -4.360021393,55.8678632586,609.6 -4.3596986219,55.8717000041,609.6 -4.3600068705,55.8755371254,609.6 -4.3609436943,55.8793418811,609.6 -4.3625012801,55.883081796,609.6 -4.364666506,55.88672493950001,609.6 -4.367421048,55.8902401984,609.6 -4.3707415313,55.8935975433,609.6 -4.3745997254,55.8967682863,609.6 -4.3789627812,55.8997253273,609.6 -4.3837935094,55.90244338659999,609.6 -4.3890506963,55.9048992227,609.6 -4.3946894557,55.907071832,609.6 -4.4006616124,55.90894262999999,609.6 -4.4069161161,55.9104956113,609.6 -4.4133994801,55.911717488,609.6 -4.4200562418,55.9125978039,609.6 -4.4268294408,55.9131290254,609.6 -4.4336611111,55.9133066058,609.6 + + + + +
+ + EGRU505B GLASGOW RWY 05 + 554945N 0043005W -
555009N 0043044W -
555047N 0042933W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to
555024N 0042853W -
554945N 0043005W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.5013388889,55.8292444444,609.6 -4.4813740556,55.8399566111,609.6 -4.4853205407,55.8419728253,609.6 -4.4889988796,55.844143751,609.6 -4.4923899444,55.8464581111,609.6 -4.5123388889,55.8357527778,609.6 -4.5013388889,55.8292444444,609.6 + + + + +
+ + EGRU505C GLASGOW RWY 23 + 555444N 0042210W -
555421N 0042130W -
555349N 0042229W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555218N 0042601W to
555412N 0042309W -
555444N 0042210W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.3693777778,55.9122694444,609.6 -4.3858671944,55.9034677222,609.6 -4.3819197029,55.9014481405,609.6 -4.3782420207,55.8992738431,609.6 -4.3748532778,55.89695616669999,609.6 -4.35835,55.90576388889999,609.6 -4.3693777778,55.9122694444,609.6 + + + + +
+ + EGRU506A CUMBERNAULD + A circle, 2 NM radius, centred at 555829N 0035832W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9754333333,56.00792252559999,609.6 -3.9815386102,56.00774605590001,609.6 -3.9875790042,56.0072185223,609.6 -3.9934903273,56.0063455309,609.6 -3.9992097732,56.00513635829999,609.6 -4.0046765897,56.00360385279999,609.6 -4.0098327274,56.0017642963,609.6 -4.0146234598,55.9996372304,609.6 -4.0189979659,55.9972452479,609.6 -4.0229098711,55.9946137503,609.6 -4.026317738,55.991770678,609.6 -4.0291855056,55.9887462108,609.6 -4.0314828677,55.98557244730001,609.6 -4.0331855908,55.9822830623,609.6 -4.0342757661,55.978912949,609.6 -4.0347419927,55.9754978476,609.6 -4.0345794927,55.9720739659,609.6 -4.0337901541,55.9686775956,609.6 -4.0323825044,55.9653447272,609.6 -4.0303716132,55.9621106691,609.6 -4.0277789261,55.9590096745,609.6 -4.0246320321,55.9560745792,609.6 -4.0209643667,55.95333645500001,609.6 -4.0168148538,55.9508242826,609.6 -4.012227492,55.9485646454,609.6 -4.0072508868,55.94658145049999,609.6 -4.0019377369,55.9448956766,609.6 -3.9963442776,55.94352515389999,609.6 -3.9905296883,55.9424843764,609.6 -3.9845554704,55.94178434989999,609.6 -3.9784848002,55.9414324764,609.6 -3.9723818665,55.9414324764,609.6 -3.9663111963,55.94178434989999,609.6 -3.9603369783,55.9424843764,609.6 -3.9545223891,55.94352515389999,609.6 -3.9489289298,55.9448956766,609.6 -3.9436157799,55.94658145049999,609.6 -3.9386391747,55.9485646454,609.6 -3.9340518128,55.9508242826,609.6 -3.9299023,55.95333645500001,609.6 -3.9262346345,55.9560745792,609.6 -3.9230877405,55.9590096745,609.6 -3.9204950535,55.9621106691,609.6 -3.9184841622,55.9653447272,609.6 -3.9170765126,55.9686775956,609.6 -3.916287174,55.9720739659,609.6 -3.9161246739,55.9754978476,609.6 -3.9165909006,55.978912949,609.6 -3.9176810758,55.9822830623,609.6 -3.919383798999999,55.98557244730001,609.6 -3.9216811611,55.9887462108,609.6 -3.9245489286,55.991770678,609.6 -3.9279567956,55.9946137503,609.6 -3.9318687007,55.9972452479,609.6 -3.9362432069,55.9996372304,609.6 -3.9410339393,56.0017642963,609.6 -3.946190077,56.00360385279999,609.6 -3.9516568934,56.00513635829999,609.6 -3.957376339400001,56.0063455309,609.6 -3.9632876624,56.0072185223,609.6 -3.9693280564,56.00774605590001,609.6 -3.9754333333,56.00792252559999,609.6 + + + + +
+ + EGRU506B CUMBERNAULD RWY 07 + 555721N 0040320W -
555752N 0040338W -
555809N 0040202W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to
555738N 0040145W -
555721N 0040320W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0556527778,55.9557666667,609.6 -4.0290868333,55.96047041670001,609.6 -4.031149962,55.9632401287,609.6 -4.0327598646,55.9661028542,609.6 -4.0339033333,55.9690353056,609.6 -4.0604583333,55.9643333333,609.6 -4.0556527778,55.9557666667,609.6 + + + + +
+ + EGRU506C CUMBERNAULD RWY 25 + 555937N 0035343W -
555906N 0035325W -
555849N 0035501W thence anti-clockwise by the arc of a circle radius 2 NM centred on 555829N 0035832W to
555920N 0035518W -
555937N 0035343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.895152777799999,55.9934916667,609.6 -3.9217423611,55.9888194444,609.6 -3.9196852867,55.9860479238,609.6 -3.9180825215,55.9831837186,609.6 -3.9169470278,55.9802501667,609.6 -3.8903416667,55.98492499999999,609.6 -3.895152777799999,55.9934916667,609.6 + + + + +
+ + EGRU507A EDINBURGH + A circle, 2.5 NM radius, centred at 555700N 0032221W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3725,55.9915838517,609.6 -3.3793454676,55.991406273,609.6 -3.3861323453,55.9908750567,609.6 -3.392802549399999,55.9899947493,609.6 -3.399299004,55.9887728846,609.6 -3.4055661343,55.9872199186,609.6 -3.411550345,55.9853491394,609.6 -3.4172004825,55.9831765523,609.6 -3.4224682743,55.9807207417,609.6 -3.4273087435,55.9780027111,609.6 -3.431680593199999,55.975045702,609.6 -3.4355465594,55.97187499390001,609.6 -3.438873727,55.9685176868,609.6 -3.4416338089,55.9650024685,609.6 -3.4438033837,55.9613593679,609.6 -3.445364091,55.95761949809999,609.6 -3.4463027832,55.9538147896,609.6 -3.446611632,55.9499777168,609.6 -3.4462881886,55.946141021,609.6 -3.4453353986,55.94233743060001,609.6 -3.4437615707,55.93859938209999,609.6 -3.4415802993,55.9349587439,609.6 -3.4388103428,55.9314465451,609.6 -3.4354754592,55.9280927121,609.6 -3.4316041982,55.92492581409999,609.6 -3.4272296552,55.9219728214,609.6 -3.422389186,55.91925887679999,609.6 -3.4171240874,55.91680708269999,609.6 -3.4114792447,55.9146383056,609.6 -3.40550275,55.9127710004,609.6 -3.3992454943,55.91122105409999,609.6 -3.3927607363,55.9100016517,609.6 -3.3861036529,55.9091231656,609.6 -3.379330872899999,55.9085930675,609.6 -3.3725,55.9084158658,609.6 -3.3656691271,55.9085930675,609.6 -3.3588963471,55.9091231656,609.6 -3.3522392637,55.9100016517,609.6 -3.3457545057,55.91122105409999,609.6 -3.33949725,55.9127710004,609.6 -3.3335207553,55.9146383056,609.6 -3.3278759126,55.91680708269999,609.6 -3.322610814,55.91925887679999,609.6 -3.3177703448,55.9219728214,609.6 -3.3133958018,55.92492581409999,609.6 -3.3095245408,55.9280927121,609.6 -3.3061896572,55.9314465451,609.6 -3.3034197007,55.9349587439,609.6 -3.3012384293,55.93859938209999,609.6 -3.2996646014,55.94233743060001,609.6 -3.2987118114,55.946141021,609.6 -3.298388368,55.9499777168,609.6 -3.2986972168,55.9538147896,609.6 -3.299635909,55.95761949809999,609.6 -3.3011966163,55.9613593679,609.6 -3.303366191099999,55.9650024685,609.6 -3.306126273,55.9685176868,609.6 -3.3094534406,55.97187499390001,609.6 -3.3133194068,55.975045702,609.6 -3.317691256499999,55.9780027111,609.6 -3.3225317257,55.9807207417,609.6 -3.3277995175,55.9831765523,609.6 -3.333449655,55.9853491394,609.6 -3.339433865699999,55.9872199186,609.6 -3.345700996,55.9887728846,609.6 -3.3521974506,55.9899947493,609.6 -3.3588676547,55.9908750567,609.6 -3.365654532399999,55.991406273,609.6 -3.3725,55.9915838517,609.6 + + + + +
+ + EGRU507B EDINBURGH RWY 06 + 555504N 0032705W -
555532N 0032735W -
555557N 0032623W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to
555529N 0032553W -
555504N 0032705W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4515083333,55.9179055556,609.6 -3.4313687778,55.9247520556,609.6 -3.4344587671,55.9271983849,609.6 -3.4372270503,55.92976332560001,609.6 -3.4396591944,55.9324335556,609.6 -3.459775,55.92559444439999,609.6 -3.4515083333,55.9179055556,609.6 + + + + +
+ + EGRU507C EDINBURGH RWY 24 + 555855N 0031737W -
555827N 0031707W -
555803N 0031819W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 555700N 0032221W to
555831N 0031849W -
555855N 0031737W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2935388889,55.9819416667,609.6 -3.3135155278,55.97519091669999,609.6 -3.3104327879,55.9727397804,609.6 -3.307673542299999,55.970170342,609.6 -3.3052520833,55.967496,609.6 -3.2852555556,55.97425277779999,609.6 -3.2935388889,55.9819416667,609.6 + + + + +
+ + EGRU508A NEWCASTLE + A circle, 2.5 NM radius, centred at 550217N 0014123W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6898111111,55.07951230690001,609.6 -1.6964999664,55.0793347079,609.6 -1.7031315782,55.0788034309,609.6 -1.7096491977,55.0779230223,609.6 -1.7159970603,55.0767010161,609.6 -1.7221208669,55.0751478684,609.6 -1.7279682522,55.0732768675,609.6 -1.7334892353,55.071104019,609.6 -1.7386366495,55.0686479081,609.6 -1.7433665467,55.065929539,609.6 -1.7476385734,55.0629721544,609.6 -1.7514163152,55.0598010353,609.6 -1.754667606,55.0564432835,609.6 -1.7573648005,55.05292758910001,609.6 -1.7594850068,55.0492839838,609.6 -1.7610102773,55.0455435839,609.6 -1.7619277575,55.0417383236,609.6 -1.7622297899,55.0379006818,609.6 -1.7619139737,55.0340634042,609.6 -1.760983179,55.0302592245,609.6 -1.7594455168,55.0265205847,609.6 -1.7573142637,55.02287935900001,609.6 -1.7546077433,55.01936658260001,609.6 -1.7513491651,55.016012188,609.6 -1.7475664227,55.01284475080001,609.6 -1.7432918523,55.0098912476,609.6 -1.7385619551,55.00717682720001,609.6 -1.7334170845,55.0047245977,609.6 -1.727901102,55.0025554312,609.6 -1.7220610041,55.0006877874,609.6 -1.7159465234,54.9991375578,609.6 -1.7096097077,54.9979179311,609.6 -1.7031044799,54.9970392826,609.6 -1.6964861825,54.99650908620001,609.6 -1.6898111111,54.9963318516,609.6 -1.6831360397,54.99650908620001,609.6 -1.6765177423,54.9970392826,609.6 -1.6700125145,54.9979179311,609.6 -1.6636756989,54.9991375578,609.6 -1.6575612182,55.0006877874,609.6 -1.6517211202,55.0025554312,609.6 -1.6462051377,55.0047245977,609.6 -1.6410602671,55.00717682720001,609.6 -1.6363303699,55.0098912476,609.6 -1.6320557995,55.01284475080001,609.6 -1.6282730571,55.016012188,609.6 -1.6250144789,55.01936658260001,609.6 -1.6223079585,55.02287935900001,609.6 -1.6201767054,55.0265205847,609.6 -1.6186390432,55.0302592245,609.6 -1.6177082486,55.0340634042,609.6 -1.6173924323,55.0379006818,609.6 -1.6176944647,55.0417383236,609.6 -1.6186119449,55.0455435839,609.6 -1.6201372155,55.0492839838,609.6 -1.6222574217,55.05292758910001,609.6 -1.6249546162,55.0564432835,609.6 -1.628205907,55.0598010353,609.6 -1.6319836488,55.0629721544,609.6 -1.6362556755,55.065929539,609.6 -1.6409855727,55.0686479081,609.6 -1.6461329869,55.071104019,609.6 -1.6516539701,55.0732768675,609.6 -1.6575013554,55.0751478684,609.6 -1.6636251619,55.0767010161,609.6 -1.6699730245,55.0779230223,609.6 -1.676490644,55.0788034309,609.6 -1.6831222558,55.0793347079,609.6 -1.6898111111,55.07951230690001,609.6 + + + + +
+ + EGRU508B NEWCASTLE RWY 07 + 550040N 0014620W -
550109N 0014644W -
550129N 0014530W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to
550059N 0014507W -
550040N 0014620W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.7723027778,55.0110388889,609.6 -1.7518513611,55.0164843056,609.6 -1.7543812399,55.0191080779,609.6 -1.7565757289,55.0218297539,609.6 -1.7584233611,55.0246351944,609.6 -1.7788555556,55.0191944444,609.6 -1.7723027778,55.0110388889,609.6 + + + + +
+ + EGRU508C NEWCASTLE RWY 25 + 550353N 0013627W -
550324N 0013603W -
550304N 0013716W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 550217N 0014123W to
550334N 0013740W -
550353N 0013627W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6074555556,55.0646833333,609.6 -1.6277036667,55.0593275,609.6 -1.6251793523,55.0567007126,609.6 -1.622991767,55.05397627000001,609.6 -1.62115225,55.0511683611,609.6 -1.6008888889,55.05652777779999,609.6 -1.6074555556,55.0646833333,609.6 + + + + +
+ + EGRU509A KIRKNEWTON + A circle, 2 NM radius, centred at 555224N 0032355W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.398525,55.906473077,609.6 -3.4046143306,55.90629660500001,609.6 -3.4106389485,55.9057690643,609.6 -3.4165348337,55.9048960612,609.6 -3.4222393447,55.9036868723,609.6 -3.4276918883,55.9021543458,609.6 -3.4328345671,55.9003147639,609.6 -3.4376127976,55.8981876682,609.6 -3.4419758918,55.8957956516,609.6 -3.4458775957,55.8931641159,609.6 -3.449276580399999,55.8903210016,609.6 -3.452136878000001,55.8872964889,609.6 -3.4544282614,55.8841226767,609.6 -3.456126559499999,55.8808332402,609.6 -3.4572139095,55.877463073,609.6 -3.4576789395,55.87404791580001,609.6 -3.4575168832,55.8706239771,609.6 -3.4567296229,55.867227549,609.6 -3.4553256631,55.8638946228,609.6 -3.4533200331,55.8606605077,609.6 -3.450734122,55.8575594574,609.6 -3.4475954465,55.8546243084,609.6 -3.4439373541,55.8518861335,609.6 -3.4397986674,55.8493739138,609.6 -3.4352232698,55.84711423360001,609.6 -3.4302596402,55.84513100060001,609.6 -3.424960340200001,55.843445194,609.6 -3.4193814587,55.84207464439999,609.6 -3.4135820215,55.8410338464,609.6 -3.40762337,55.84033380610001,609.6 -3.4015685166,55.83998192559999,609.6 -3.3954814834,55.83998192559999,609.6 -3.38942663,55.84033380610001,609.6 -3.3834679785,55.8410338464,609.6 -3.3776685413,55.84207464439999,609.6 -3.372089659799999,55.843445194,609.6 -3.3667903598,55.84513100060001,609.6 -3.3618267302,55.84711423360001,609.6 -3.3572513326,55.8493739138,609.6 -3.3531126459,55.8518861335,609.6 -3.3494545535,55.8546243084,609.6 -3.346315878,55.8575594574,609.6 -3.3437299669,55.8606605077,609.6 -3.3417243369,55.8638946228,609.6 -3.3403203771,55.867227549,609.6 -3.3395331168,55.8706239771,609.6 -3.3393710605,55.87404791580001,609.6 -3.3398360905,55.877463073,609.6 -3.3409234405,55.8808332402,609.6 -3.3426217386,55.8841226767,609.6 -3.344913122,55.8872964889,609.6 -3.3477734196,55.8903210016,609.6 -3.3511724043,55.8931641159,609.6 -3.3550741082,55.8957956516,609.6 -3.3594372024,55.8981876682,609.6 -3.3642154329,55.9003147639,609.6 -3.3693581117,55.9021543458,609.6 -3.3748106553,55.9036868723,609.6 -3.3805151663,55.9048960612,609.6 -3.386411051500001,55.9057690643,609.6 -3.3924356694,55.90629660500001,609.6 -3.398525,55.906473077,609.6 + + + + +
+ + EGRU510 HMP NORTHUMBERLAND + 551818N 0013757W -
551756N 0013719W -
551743N 0013716W -
551716N 0013805W -
551720N 0013839W -
551737N 0013910W -
551818N 0013757W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 118 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6326027778,55.3049305556,182.88 -1.6528194444,55.2935,182.88 -1.6441694444,55.2888166667,182.88 -1.63475,55.2877805556,182.88 -1.6210055556,55.2953416667,182.88 -1.6220055556,55.2989555556,182.88 -1.6326027778,55.3049305556,182.88 + + + + +
+ + EGRU601A TIREE + A circle, 2 NM radius, centred at 562957N 0065209W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.8691666667,56.53243079859999,609.6 -6.8753560547,56.5322543409,609.6 -6.8814796627,56.5317268434,609.6 -6.8874724149,56.5308539119,609.6 -6.893270637199999,56.52964482310001,609.6 -6.898812738,56.5281124248,609.6 -6.9040398665,56.52627299859999,609.6 -6.9088965412,56.5241460857,609.6 -6.9133312409,56.5217542778,609.6 -6.917296952700001,56.5191229759,609.6 -6.92075167,56.5162801189,609.6 -6.9236588372,56.5132558855,609.6 -6.9259877337,56.5100823723,609.6 -6.9277137958,56.50679325229999,609.6 -6.928818872,56.5034234163,609.6 -6.9292914089,56.5000086018,609.6 -6.929126567,56.4965850139,609.6 -6.9283262651,56.4931889409,609.6 -6.926899152099999,56.4898563701,609.6 -6.9248605091,56.4866226063,609.6 -6.922232080200001,56.4835218989,609.6 -6.9190418369,56.4805870799,609.6 -6.9153236767,56.4778492177,609.6 -6.9111170607,56.47533728890001,609.6 -6.906466592800001,56.4730778737,609.6 -6.901421547,56.4710948757,609.6 -6.8960353454,56.46940927090001,609.6 -6.890364994899999,56.4680388867,609.6 -6.884470486200001,56.466998215,609.6 -6.8784141631,56.46629826,609.6 -6.8722600672,56.4659464225,609.6 -6.8660732661,56.4659464225,609.6 -6.8599191702,56.46629826,609.6 -6.8538628471,56.466998215,609.6 -6.8479683384,56.4680388867,609.6 -6.842297987900001,56.46940927090001,609.6 -6.836911786400001,56.4710948757,609.6 -6.8318667405,56.4730778737,609.6 -6.827216272600001,56.47533728890001,609.6 -6.823009656600001,56.4778492177,609.6 -6.8192914965,56.4805870799,609.6 -6.8161012532,56.4835218989,609.6 -6.8134728243,56.4866226063,609.6 -6.8114341812,56.4898563701,609.6 -6.8100070682,56.4931889409,609.6 -6.809206766299999,56.4965850139,609.6 -6.8090419244,56.5000086018,609.6 -6.8095144613,56.5034234163,609.6 -6.8106195375,56.50679325229999,609.6 -6.8123455996,56.5100823723,609.6 -6.814674496100001,56.5132558855,609.6 -6.8175816633,56.5162801189,609.6 -6.821036380700001,56.5191229759,609.6 -6.8250020924,56.5217542778,609.6 -6.829436792200001,56.5241460857,609.6 -6.8342934669,56.52627299859999,609.6 -6.8395205953,56.5281124248,609.6 -6.8450626961,56.52964482310001,609.6 -6.8508609184,56.5308539119,609.6 -6.8568536707,56.5317268434,609.6 -6.862977278600001,56.5322543409,609.6 -6.8691666667,56.53243079859999,609.6 + + + + +
+ + EGRU601B TIREE RWY 05 + 562739N 0065554W -
562803N 0065634W -
562848N 0065506W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
562824N 0065426W -
562739N 0065554W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.9317583333,56.4608361111,609.6 -6.9072867778,56.47344325,609.6 -6.9113222392,56.4754483478,609.6 -6.915015145399999,56.477646477,609.6 -6.9183354167,56.4800197778,609.6 -6.9428,56.4674138889,609.6 -6.9317583333,56.4608361111,609.6 + + + + +
+ + EGRU601C TIREE RWY 23 + 563213N 0064828W -
563149N 0064748W -
563106N 0064912W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
563130N 0064952W -
563213N 0064828W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.807697222199999,56.5368638889,609.6 -6.831034250000001,56.5248960833,609.6 -6.8269941803,56.5228900067,609.6 -6.8232981894,56.5206906729,609.6 -6.8199763611,56.5183160278,609.6 -6.7966305556,56.5302861111,609.6 -6.807697222199999,56.5368638889,609.6 + + + + +
+ + EGRU601D TIREE RWY 11 + 563040N 0065734W -
563111N 0065716W -
563051N 0065522W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
563021N 0065541W -
563040N 0065734W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.959330555599999,56.5110166667,609.6 -6.9281294444,56.5057391389,609.6 -6.9268188412,56.50865455729999,609.6 -6.925037655700001,56.5114926778,609.6 -6.922800333299999,56.51423033329999,609.6 -6.954561111099999,56.51960277780001,609.6 -6.959330555599999,56.5110166667,609.6 + + + + +
+ + EGRU601E TIREE RWY 29 + 562928N 0064712W -
562857N 0064730W -
562911N 0064849W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562957N 0065209W to
562942N 0064834W -
562928N 0064712W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.7867861111,56.4911138889,609.6 -6.809503250000001,56.4949871389,609.6 -6.8104304407,56.4920271763,609.6 -6.8118364249,56.4891255438,609.6 -6.813709611100001,56.4863058889,609.6 -6.79155,56.4825277778,609.6 -6.7867861111,56.4911138889,609.6 + + + + +
+ + EGRU602A COLL + A circle, 2 NM radius, centred at 563607N 0063704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.6177444444,56.6353302443,609.6 -6.6239506685,56.635153789,609.6 -6.6300909328,56.6346262985,609.6 -6.6360999842,56.63375337869999,609.6 -6.6419139746,56.6325443062,609.6 -6.6474711444,56.6310119287,609.6 -6.6527124825,56.6291725279,609.6 -6.657582356300001,56.6270456447,609.6 -6.6620291044,56.62465387080001,609.6 -6.666005586100001,56.622022607,609.6 -6.6694696809,56.61917979190001,609.6 -6.6723847342,56.61615560399999,609.6 -6.6747199424,56.6129821396,609.6 -6.6764506758,56.60969307130001,609.6 -6.677558734399999,56.6063232894,609.6 -6.678032533999999,56.6029085309,609.6 -6.677867223200001,56.5994850003,609.6 -6.677064726499999,56.59608898550001,609.6 -6.6756337175,56.59275647279999,609.6 -6.6735895195,56.5895227666,609.6 -6.6709539363,56.5864221154,609.6 -6.667755016099999,56.5834873505,609.6 -6.6640267488,56.5807495395,609.6 -6.659808703,56.5782376584,609.6 -6.6551456038,56.5759782867,609.6 -6.650086859,56.5739953273,609.6 -6.6446860355,56.5723097556,609.6 -6.6390002947,56.57093939850001,609.6 -6.633089789499999,56.56989874749999,609.6 -6.6270170324,56.5691988065,609.6 -6.6208462383,56.5688469761,609.6 -6.6146426506,56.5688469761,609.6 -6.608471856499999,56.5691988065,609.6 -6.6023990994,56.56989874749999,609.6 -6.5964885942,56.57093939850001,609.6 -6.5908028534,56.5723097556,609.6 -6.5854020299,56.5739953273,609.6 -6.580343285100001,56.5759782867,609.6 -6.5756801859,56.5782376584,609.6 -6.5714621401,56.5807495395,609.6 -6.567733872799999,56.5834873505,609.6 -6.564534952600001,56.5864221154,609.6 -6.561899369399999,56.5895227666,609.6 -6.5598551714,56.59275647279999,609.6 -6.5584241624,56.59608898550001,609.6 -6.5576216657,56.5994850003,609.6 -6.557456354899999,56.6029085309,609.6 -6.5579301545,56.6063232894,609.6 -6.559038213000001,56.60969307130001,609.6 -6.560768946499999,56.6129821396,609.6 -6.563104154700001,56.61615560399999,609.6 -6.566019208,56.61917979190001,609.6 -6.5694833028,56.622022607,609.6 -6.5734597845,56.62465387080001,609.6 -6.5779065326,56.6270456447,609.6 -6.5827764064,56.6291725279,609.6 -6.588017744500001,56.6310119287,609.6 -6.5935749143,56.6325443062,609.6 -6.5993889047,56.63375337869999,609.6 -6.6053979561,56.6346262985,609.6 -6.6115382204,56.635153789,609.6 -6.6177444444,56.6353302443,609.6 + + + + +
+ + EGRU603A COLONSAY + A circle, 2 NM radius, centred at 560327N 0061435W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2430777778,56.0908304089,609.6 -6.2491961631,56.0906539411,609.6 -6.2552495257,56.0901264132,609.6 -6.2611735392,56.0892534313,609.6 -6.266905262099999,56.08804427210001,609.6 -6.2723838114,56.0865117836,609.6 -6.2775510128,56.0846722478,609.6 -6.2823520222,56.08254520639999,609.6 -6.286735909399999,56.08015325149999,609.6 -6.2906562002,56.07752178509999,609.6 -6.2940713687,56.0746787469,609.6 -6.2969452767,56.07165431689999,609.6 -6.299247553499999,56.06848059310001,609.6 -6.3009539141,56.0651912502,609.6 -6.302046411800001,56.0618211809,609.6 -6.302513622,56.058406125,609.6 -6.3023507571,56.0549822899,609.6 -6.301559710099999,56.05158596670001,609.6 -6.3001490272,56.0482531455,609.6 -6.2981338111,56.045019134,609.6 -6.295535553800001,56.0419181849,609.6 -6.2923819039,56.0389831333,609.6 -6.288706369,56.0362450506,609.6 -6.2845479568,56.0337329167,609.6 -6.279950759999999,56.03147331469999,609.6 -6.274963488399999,56.029490151,609.6 -6.2696389535,56.0278044039,609.6 -6.264033510699999,56.0264339031,609.6 -6.2582064661,56.0253931423,609.6 -6.252219452,56.0246931271,609.6 -6.24613578,56.02434125929999,609.6 -6.240019775500001,56.02434125929999,609.6 -6.2339361035,56.0246931271,609.6 -6.2279490895,56.0253931423,609.6 -6.222122044900001,56.0264339031,609.6 -6.2165166021,56.0278044039,609.6 -6.2111920672,56.029490151,609.6 -6.206204795600001,56.03147331469999,609.6 -6.2016075988,56.0337329167,609.6 -6.197449186499999,56.0362450506,609.6 -6.1937736516,56.0389831333,609.6 -6.190620001799999,56.0419181849,609.6 -6.1880217445,56.045019134,609.6 -6.1860065283,56.0482531455,609.6 -6.1845958455,56.05158596670001,609.6 -6.1838047984,56.0549822899,609.6 -6.1836419335,56.058406125,609.6 -6.184109143800001,56.0618211809,609.6 -6.1852016415,56.0651912502,609.6 -6.1869080021,56.06848059310001,609.6 -6.1892102788,56.07165431689999,609.6 -6.1920841868,56.0746787469,609.6 -6.1954993554,56.07752178509999,609.6 -6.1994196462,56.08015325149999,609.6 -6.2038035334,56.08254520639999,609.6 -6.2086045427,56.0846722478,609.6 -6.2137717441,56.0865117836,609.6 -6.2192502934,56.08804427210001,609.6 -6.224982016399999,56.0892534313,609.6 -6.230906029899999,56.0901264132,609.6 -6.2369593925,56.0906539411,609.6 -6.2430777778,56.0908304089,609.6 + + + + +
+ + EGRU604A OBAN + A circle, 2 NM radius, centred at 562749N 0052400W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3998638889,56.4969837675,609.6 -5.406047503,56.49680730899999,609.6 -5.4121653987,56.4962798091,609.6 -5.4181525612,56.4954068736,609.6 -5.4239453758,56.4941977792,609.6 -5.4294823086,56.49266537370001,609.6 -5.4347045639,56.4908259387,609.6 -5.439556712,56.4886990155,609.6 -5.4439872797,56.4863071959,609.6 -5.4479492979,56.4836758809,609.6 -5.4514007993,56.48083300939999,609.6 -5.4543052619,56.4778087602,609.6 -5.4566319937,56.4746352302,609.6 -5.4583564538,56.4713460924,609.6 -5.4594605072,56.4679762377,609.6 -5.459932611,56.4645614039,609.6 -5.45976793,56.46113779620001,609.6 -5.4589683807,56.45774170319999,609.6 -5.4575426038,56.45440911229999,609.6 -5.4555058658,56.4511753287,609.6 -5.4528798905,56.4480746019,609.6 -5.4496926229,56.44513976439999,609.6 -5.445977929,56.4424018844,609.6 -5.4417752329,56.4398899392,609.6 -5.4371290969,56.43763050900001,609.6 -5.4320887491,56.4356474978,609.6 -5.4267075622,56.4339618815,609.6 -5.4210424898,56.432591488,609.6 -5.4151534672,56.43155080910001,609.6 -5.4091027801,56.43085084929999,609.6 -5.4029544109,56.4304990094,609.6 -5.3967733668,56.4304990094,609.6 -5.3906249977,56.43085084929999,609.6 -5.3845743106,56.43155080910001,609.6 -5.3786852879,56.432591488,609.6 -5.3730202156,56.4339618815,609.6 -5.3676390286,56.4356474978,609.6 -5.3625986809,56.43763050900001,609.6 -5.3579525449,56.4398899392,609.6 -5.3537498487,56.4424018844,609.6 -5.3500351548,56.44513976439999,609.6 -5.3468478873,56.4480746019,609.6 -5.3442219119,56.4511753287,609.6 -5.342185174,56.45440911229999,609.6 -5.3407593971,56.45774170319999,609.6 -5.3399598478,56.46113779620001,609.6 -5.3397951668,56.4645614039,609.6 -5.3402672706,56.4679762377,609.6 -5.341371324,56.4713460924,609.6 -5.3430957841,56.4746352302,609.6 -5.3454225159,56.4778087602,609.6 -5.3483269785,56.48083300939999,609.6 -5.3517784799,56.4836758809,609.6 -5.3557404981,56.4863071959,609.6 -5.3601710658,56.4886990155,609.6 -5.3650232139,56.4908259387,609.6 -5.3702454692,56.49266537370001,609.6 -5.375782402,56.4941977792,609.6 -5.3815752166,56.4954068736,609.6 -5.3875623791,56.4962798091,609.6 -5.3936802747,56.49680730899999,609.6 -5.3998638889,56.4969837675,609.6 + + + + +
+ + EGRU604B OBAN RWY 01 + 562451N 0052402W -
562454N 0052500W -
562553N 0052449W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to
562550N 0052351W -
562451N 0052402W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.4004833333,56.4140361111,609.6 -5.3975838056,56.4304789167,609.6 -5.4030012099,56.4305003651,609.6 -5.4083931319,56.4307920761,609.6 -5.4137157778,56.4313516944,609.6 -5.4166083333,56.4149083333,609.6 -5.4004833333,56.4140361111,609.6 + + + + +
+ + EGRU604C OBAN RWY 19 + 563046N 0052358W -
563043N 0052300W -
562946N 0052310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562749N 0052400W to
562949N 0052408W -
563046N 0052358W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -5.3993666667,56.5127111111,609.6 -5.4021495278,56.4969597222,609.6 -5.3967225023,56.49693832589999,609.6 -5.3913211261,56.4966461693,609.6 -5.3859895,56.49608563889999,609.6 -5.3832,56.51183611110001,609.6 -5.3993666667,56.5127111111,609.6 + + + + +
+ + EGRU605A PERTH/SCONE + A circle, 2 NM radius, centred at 562628N 0032226W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3739055556,56.4743894449,609.6 -3.3800854962,56.4742129859,609.6 -3.3861997576,56.47368548440001,609.6 -3.3921833637,56.4728125464,609.6 -3.3979727379,56.4716034484,609.6 -3.4035063827,56.47007103829999,609.6 -3.4087255376,56.4682315978,609.6 -3.413574805700001,56.466104668,609.6 -3.4180027446,56.4637128409,609.6 -3.4219624129,56.46108151749999,609.6 -3.4254118681,56.4582386368,609.6 -3.428314610000001,56.45521437759999,609.6 -3.4306399647,56.4520408369,609.6 -3.4323634055,56.4487516877,609.6 -3.4334668082,56.44538182109999,609.6 -3.4339386364,56.44196697489999,609.6 -3.4337740577,56.43854335459999,609.6 -3.4329749872,56.43514724890001,609.6 -3.4315500604,56.43181464519999,609.6 -3.4295145345,56.4285808489,609.6 -3.4268901202,56.42548010980001,609.6 -3.4237047459,56.4225452604,609.6 -3.4199922572,56.4198073692,609.6 -3.415792055,56.4172954134,609.6 -3.4111486751,56.4150359737,609.6 -3.4061113164,56.413052954,609.6 -3.4007333198,56.41136733050001,609.6 -3.3950716055,56.409996931,609.6 -3.3891860732,56.4089562476,609.6 -3.383138971899999,56.4082562846,609.6 -3.3769942462,56.4079044432,609.6 -3.3708168649,56.4079044432,609.6 -3.3646721392,56.4082562846,609.6 -3.3586250379,56.4089562476,609.6 -3.3527395056,56.409996931,609.6 -3.3470777913,56.41136733050001,609.6 -3.341699794699999,56.413052954,609.6 -3.336662436,56.4150359737,609.6 -3.3320190561,56.4172954134,609.6 -3.3278188539,56.4198073692,609.6 -3.3241063652,56.4225452604,609.6 -3.3209209909,56.42548010980001,609.6 -3.318296576599999,56.4285808489,609.6 -3.316261050700001,56.43181464519999,609.6 -3.3148361239,56.43514724890001,609.6 -3.3140370534,56.43854335459999,609.6 -3.3138724747,56.44196697489999,609.6 -3.314344303,56.44538182109999,609.6 -3.3154477056,56.4487516877,609.6 -3.3171711464,56.4520408369,609.6 -3.3194965011,56.45521437759999,609.6 -3.322399243,56.4582386368,609.6 -3.325848698300001,56.46108151749999,609.6 -3.3298083665,56.4637128409,609.6 -3.3342363054,56.466104668,609.6 -3.3390855735,56.4682315978,609.6 -3.3443047284,56.47007103829999,609.6 -3.3498383732,56.4716034484,609.6 -3.3556277474,56.4728125464,609.6 -3.3616113535,56.47368548440001,609.6 -3.3677256149,56.4742129859,609.6 -3.3739055556,56.4743894449,609.6 + + + + +
+ + EGRU605B PERTH/SCONE RWY 03 + 562346N 0032431W -
562401N 0032522W -
562451N 0032433W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562436N 0032342W -
562346N 0032431W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4084972222,56.39609166669999,609.6 -3.3949996667,56.4099819444,609.6 -3.3999783657,56.4111619804,609.6 -3.4047452434,56.4125858503,609.6 -3.4092615556,56.4142419722,609.6 -3.422750000000001,56.40035555560001,609.6 -3.4084972222,56.39609166669999,609.6 + + + + +
+ + EGRU605C PERTH/SCONE RWY 21 + 562910N 0032021W -
562855N 0031930W -
562805N 0032019W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562820N 0032110W -
562910N 0032021W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3392388889,56.4861444444,609.6 -3.3527793333,56.47226480560001,609.6 -3.3477937836,56.47108294669999,609.6 -3.3430213946,56.46965693160001,609.6 -3.3385010833,56.4679984167,609.6 -3.3249527778,56.4818805556,609.6 -3.3392388889,56.4861444444,609.6 + + + + +
+ + EGRU605D PERTH/SCONE RWY 09 + 562554N 0032720W -
562627N 0032721W -
562628N 0032602W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562556N 0032554W -
562554N 0032720W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4554361111,56.4317694444,609.6 -3.4317364167,56.43217586109999,609.6 -3.4329649966,56.4351170685,609.6 -3.4337073317,56.4381078709,609.6 -3.4339572222,56.4411236389,609.6 -3.4559194444,56.4407472222,609.6 -3.4554361111,56.4317694444,609.6 + + + + +
+ + EGRU605E PERTH/SCONE RWY 27 + 562637N 0031711W -
562604N 0031709W -
562603N 0031855W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562635N 0031850W -
562637N 0031711W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2863305556,56.4435527778,609.6 -3.3139595278,56.4431115278,609.6 -3.3138835923,56.4400935224,609.6 -3.3143017912,56.43708412620001,609.6 -3.3152105556,56.4341081111,609.6 -3.2858444444,56.4345777778,609.6 -3.2863305556,56.4435527778,609.6 + + + + +
+ + EGRU605F PERTH/SCONE RWY 15 + 562844N 0032509W -
562900N 0032418W -
562821N 0032337W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562806N 0032429W -
562844N 0032509W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.419075,56.47875,609.6 -3.408111277799999,56.4684703889,609.6 -3.4035104538,56.4700697543,609.6 -3.3986671264,56.4714324112,609.6 -3.3936209444,56.47254719439999,609.6 -3.4050944444,56.4833083333,609.6 -3.419075,56.47875,609.6 + + + + +
+ + EGRU605G PERTH/SCONE RWY 33 + 562404N 0031904W -
562348N 0031954W -
562441N 0032050W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562628N 0032226W to
562459N 0032002W -
562404N 0031904W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.317663888899999,56.401125,609.6 -3.3338338333,56.41635597220001,609.6 -3.3380343685,56.41445234959999,609.6 -3.3425274864,56.4127666313,609.6 -3.3472765278,56.4113125833,609.6 -3.3316138889,56.3965638889,609.6 -3.317663888899999,56.401125,609.6 + + + + +
+ + EGRU606A DUNDEE + A circle, 2 NM radius, centred at 562709N 0030133W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0258333333,56.4857643835,609.6 -3.0320151227,56.48558792480001,609.6 -3.0381312131,56.48506042409999,609.6 -3.044116609,56.4841874874,609.6 -3.0499077146,56.4829783912,609.6 -3.0554430142,56.48144598340001,609.6 -3.0606637293,56.47960654569999,609.6 -3.0655144468,56.4774796192,609.6 -3.0699437087,56.4750877959,609.6 -3.0739045596,56.4724564767,609.6 -3.0773550446,56.4696136006,609.6 -3.0802586524,56.4665893465,609.6 -3.0825847002,56.4634158112,609.6 -3.084308654,56.4601266677,609.6 -3.085412384100001,56.4567568071,609.6 -3.085884351,56.45334196709999,609.6 -3.0857197208,56.4499183532,609.6 -3.0849204094,56.4465222539,609.6 -3.083495054800001,56.4431896566,609.6 -3.0814589189,56.4399558667,609.6 -3.078833719,56.4368551338,609.6 -3.0756473919,56.43392029030001,609.6 -3.0719337934,56.4311824048,609.6 -3.067732336,56.42867045439999,609.6 -3.0630875691,56.4264110194,609.6 -3.0580487061,56.424428004,609.6 -3.052669104,56.4227423841,609.6 -3.0470056997,56.4213719876,609.6 -3.0411184109,56.4203313065,609.6 -3.035069505,56.41963134520001,609.6 -3.0289229457,56.41927950449999,609.6 -3.022743721,56.41927950449999,609.6 -3.0165971617,56.41963134520001,609.6 -3.0105482558,56.4203313065,609.6 -3.0046609669,56.4213719876,609.6 -2.998997562700001,56.4227423841,609.6 -2.9936179605,56.424428004,609.6 -2.9885790975,56.4264110194,609.6 -2.9839343306,56.42867045439999,609.6 -2.9797328733,56.4311824048,609.6 -2.9760192748,56.43392029030001,609.6 -2.9728329477,56.4368551338,609.6 -2.9702077478,56.4399558667,609.6 -2.9681716119,56.4431896566,609.6 -2.9667462573,56.4465222539,609.6 -2.9659469459,56.4499183532,609.6 -2.9657823156,56.45334196709999,609.6 -2.9662542826,56.4567568071,609.6 -2.9673580127,56.4601266677,609.6 -2.9690819665,56.4634158112,609.6 -2.9714080142,56.4665893465,609.6 -2.9743116221,56.4696136006,609.6 -2.9777621071,56.4724564767,609.6 -2.981722958000001,56.4750877959,609.6 -2.9861522199,56.4774796192,609.6 -2.9910029373,56.47960654569999,609.6 -2.9962236525,56.48144598340001,609.6 -3.001758951999999,56.4829783912,609.6 -3.0075500577,56.4841874874,609.6 -3.0135354536,56.48506042409999,609.6 -3.0196515439,56.48558792480001,609.6 -3.0258333333,56.4857643835,609.6 + + + + +
+ + EGRU606B DUNDEE RWY 09 + 562654N 0030706W -
562726N 0030705W -
562726N 0030507W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to
562654N 0030507W -
562654N 0030706W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.1183416667,56.44835,609.6 -3.0853967222,56.4482048333,609.6 -3.0858557268,56.4511958568,609.6 -3.0858259999,56.4541976161,609.6 -3.0853076667,56.4571856667,609.6 -3.1181916667,56.4573305556,609.6 -3.1183416667,56.44835,609.6 + + + + +
+ + EGRU606C DUNDEE RWY 27 + 562723N 0025600W -
562651N 0025600W -
562651N 0025759W thence anti-clockwise by the arc of a circle radius 2 NM centred on 562709N 0030133W to
562724N 0025758W -
562723N 0025600W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9333166667,56.4564027778,609.6 -2.9662158889,56.4565880278,609.6 -2.9657954518,56.45359527630001,609.6 -2.9658639633,56.45059372160001,609.6 -2.966420750000001,56.4476078056,609.6 -2.9334611111,56.4474222222,609.6 -2.9333166667,56.4564027778,609.6 + + + + +
+ + EGRU607A LEUCHARS + A circle, 2.5 NM radius, centred at 562230N 0025132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8587805556,56.41647264160001,609.6 -2.8657021278,56.4162950721,609.6 -2.8725644557,56.4157638834,609.6 -2.879308806800001,56.41488362209999,609.6 -2.8858774683,56.4136618219,609.6 -2.892214244899999,56.4121089388,609.6 -2.8982649438,56.4102382607,609.6 -2.9039778414,56.4080657928,609.6 -2.9093041281,56.4056101194,609.6 -2.914198326699999,56.4028922436,609.6 -2.9186186821,56.39993540649999,609.6 -2.9225275174,56.39676488679999,609.6 -2.925891553600001,56.39340778380001,609.6 -2.928682191900001,56.3898927841,609.6 -2.9308757535,56.3862499157,609.6 -2.9324536776,56.38251029,609.6 -2.9334026742,56.37870583559999,609.6 -2.9337148321,56.3748690254,609.6 -2.9333876794,56.3710325982,609.6 -2.9324241985,56.3672292802,609.6 -2.9308327941,56.3634915053,609.6 -2.928627215100001,56.3598511391,609.6 -2.9258264316,56.356339208,609.6 -2.9224544677,56.35298563530001,609.6 -2.9185401925,56.34981898749999,609.6 -2.9141170699,56.3468662319,609.6 -2.9092228713,56.34415250829999,609.6 -2.9038993517,56.34170091650001,609.6 -2.8981918941,56.33953232050001,609.6 -2.892149122699999,56.3376651727,609.6 -2.8858224914,56.3361153582,609.6 -2.8792658473,56.3348960602,609.6 -2.8725349765,56.3340176497,609.6 -2.8656871329,56.3334875974,609.6 -2.8587805556,56.333310411,609.6 -2.8518739782,56.3334875974,609.6 -2.8450261346,56.3340176497,609.6 -2.8382952638,56.3348960602,609.6 -2.8317386198,56.3361153582,609.6 -2.8254119884,56.3376651727,609.6 -2.8193692171,56.33953232050001,609.6 -2.8136617594,56.34170091650001,609.6 -2.8083382398,56.34415250829999,609.6 -2.8034440412,56.3468662319,609.6 -2.7990209186,56.34981898749999,609.6 -2.7951066434,56.35298563530001,609.6 -2.7917346795,56.356339208,609.6 -2.788933896,56.3598511391,609.6 -2.786728317,56.3634915053,609.6 -2.7851369126,56.3672292802,609.6 -2.7841734317,56.3710325982,609.6 -2.783846279,56.3748690254,609.6 -2.7841584369,56.37870583559999,609.6 -2.7851074336,56.38251029,609.6 -2.7866853576,56.3862499157,609.6 -2.7888789192,56.3898927841,609.6 -2.7916695575,56.39340778380001,609.6 -2.7950335937,56.39676488679999,609.6 -2.798942429,56.39993540649999,609.6 -2.8033627844,56.4028922436,609.6 -2.808256983,56.4056101194,609.6 -2.8135832697,56.4080657928,609.6 -2.819296167300001,56.4102382607,609.6 -2.8253468662,56.4121089388,609.6 -2.8316836428,56.4136618219,609.6 -2.8382523043,56.41488362209999,609.6 -2.8449966554,56.4157638834,609.6 -2.8518589833,56.4162950721,609.6 -2.8587805556,56.41647264160001,609.6 + + + + +
+ + EGRU607B LEUCHARS RWY 04 + 561957N 0025452W -
562017N 0025539W -
562050N 0025453W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562028N 0025410W -
561957N 0025452W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9144206944,56.3325690833,609.6 -2.9027777778,56.34124019439999,609.6 -2.9070505126,56.3430960833,609.6 -2.9110705021,56.3451187835,609.6 -2.9148166667,56.3472976944,609.6 -2.9273748889,56.33794275,609.6 -2.9144206944,56.3325690833,609.6 + + + + +
+ + EGRU607C LEUCHARS RWY 22 + 562509N 0024905W -
562449N 0024819W -
562428N 0024847W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562445N 0024937W -
562509N 0024905W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8181688333,56.41909744439999,609.6 -2.826999194399999,56.4125516667,609.6 -2.822164781200001,56.4111759222,609.6 -2.8175231097,56.4096095711,609.6 -2.8130985833,56.40786086109999,609.6 -2.8051870833,56.4137238333,609.6 -2.8181688333,56.41909744439999,609.6 + + + + +
+ + EGRU607D LEUCHARS RWY 08 + 562145N 0025723W -
562217N 0025731W -
562224N 0025601W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562152N 0025553W -
562145N 0025723W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9562513333,56.36250361110001,609.6 -2.9313368611,56.36452075,609.6 -2.9324977062,56.3674495154,609.6 -2.9332753622,56.37041709300001,609.6 -2.9336656944,56.37340805560001,609.6 -2.9585670556,56.3713919722,609.6 -2.9562513333,56.36250361110001,609.6 + + + + +
+ + EGRU607E LEUCHARS RWY 26 + 562314N 0024541W -
562242N 0024532W -
562235N 0024702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 562230N 0025132W to
562307N 0024710W -
562314N 0024541W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7612772778,56.3872223611,609.6 -2.7861945833,56.38524102780001,609.6 -2.7850416753,56.3823112446,609.6 -2.7842725202,56.3793429756,609.6 -2.7838910278,56.3763516667,609.6 -2.7589605833,56.3783340278,609.6 -2.7612772778,56.3872223611,609.6 + + + + +
+ + EGRU701A BARRA + A circle, 2 NM radius, centred at 570122N 0072635W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.4430555556,57.0560390985,609.6 -7.4493317926,57.0558626526,609.6 -7.455541323000001,57.0553351905,609.6 -7.4616181547,57.05446231799999,609.6 -7.4674977172,57.0532533114,609.6 -7.473117551999999,57.0517210185,609.6 -7.478417981,57.0498817204,609.6 -7.4833427432,57.0477549579,609.6 -7.4878395942,57.045363322,609.6 -7.491860862,57.04273221289999,609.6 -7.495363952599999,57.0398895683,609.6 -7.4983117994,57.0368655654,609.6 -7.5006732542,57.0336922995,609.6 -7.502423412400001,57.0304034414,609.6 -7.503543871900001,57.0270338796,609.6 -7.5040229219,57.0236193492,609.6 -7.5038556597,57.0201960523,609.6 -7.5030440356,57.0168002742,609.6 -7.5015968243,57.01346799859999,609.6 -7.499529525,57.01023452690001,609.6 -7.4968641904,57.0071341048,609.6 -7.4936291869,57.0041995606,609.6 -7.489858889200001,57.0014619587,609.6 -7.4855933127,56.9989502723,609.6 -7.4808776867,56.996691078,609.6 -7.475761975199999,56.9947082762,609.6 -7.4703003474,56.99302283969999,609.6 -7.4645506066,56.9916525934,609.6 -7.4585735812,56.9906120271,609.6 -7.4524324849,56.9899121433,609.6 -7.4461922524,56.98956034169999,609.6 -7.4399188587,56.98956034169999,609.6 -7.4336786262,56.9899121433,609.6 -7.4275375299,56.9906120271,609.6 -7.4215605045,56.9916525934,609.6 -7.4158107637,56.99302283969999,609.6 -7.410349136000001,56.9947082762,609.6 -7.4052334244,56.996691078,609.6 -7.4005177984,56.9989502723,609.6 -7.396252221899999,57.0014619587,609.6 -7.3924819242,57.0041995606,609.6 -7.3892469207,57.0071341048,609.6 -7.3865815861,57.01023452690001,609.6 -7.3845142869,57.01346799859999,609.6 -7.3830670755,57.0168002742,609.6 -7.3822554514,57.0201960523,609.6 -7.3820881892,57.0236193492,609.6 -7.382567239199999,57.0270338796,609.6 -7.383687698699999,57.0304034414,609.6 -7.3854378569,57.0336922995,609.6 -7.3877993117,57.0368655654,609.6 -7.390747158500001,57.0398895683,609.6 -7.3942502491,57.04273221289999,609.6 -7.3982715169,57.045363322,609.6 -7.4027683679,57.0477549579,609.6 -7.4076931301,57.0498817204,609.6 -7.412993559100001,57.0517210185,609.6 -7.4186133939,57.0532533114,609.6 -7.4244929564,57.05446231799999,609.6 -7.430569788099999,57.0553351905,609.6 -7.4367793185,57.0558626526,609.6 -7.4430555556,57.0560390985,609.6 + + + + +
+ + EGRU701B BARRA RWY 07 + 570009N 0073107W -
570038N 0073131W -
570058N 0073010W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570027N 0072950W -
570009N 0073107W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.518661111100001,57.00238055560001,609.6 -7.4972838889,57.0075711389,609.6 -7.499584313799999,57.01030810419999,609.6 -7.5014219593,57.0131473248,609.6 -7.5027816667,57.0160655556,609.6 -7.5253361111,57.01058888890001,609.6 -7.518661111100001,57.00238055560001,609.6 + + + + +
+ + EGRU701C BARRA RWY 25 + 570300N 0072146W -
570230N 0072122W -
570204N 0072310W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570233N 0072338W -
570300N 0072146W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.362816666700001,57.049925,609.6 -7.39384875,57.04243672220001,609.6 -7.390790637700001,57.039929051,609.6 -7.3881615015,57.0372808229,609.6 -7.385982805600001,57.0345137778,609.6 -7.3561305556,57.0417166667,609.6 -7.362816666700001,57.049925,609.6 + + + + +
+ + EGRU701D BARRA RWY 11 + 570143N 0073151W -
570214N 0073140W -
570204N 0073000W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570133N 0073014W -
570143N 0073151W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.5307805556,57.0285111111,609.6 -7.5037998333,57.02575224999999,609.6 -7.5030623655,57.02872919030001,609.6 -7.501835202200001,57.0316576943,609.6 -7.50012825,57.0345138611,609.6 -7.5277277778,57.03733611109999,609.6 -7.5307805556,57.0285111111,609.6 + + + + +
+ + EGRU701E BARRA RWY 29 + 570111N 0072125W -
570039N 0072136W -
570049N 0072304W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570121N 0072255W -
570111N 0072125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.356827777800001,57.0197555556,609.6 -7.3820743056,57.0223684167,609.6 -7.382393158600001,57.0193695108,609.6 -7.383206654499999,57.0163985197,609.6 -7.3845080556,57.0134796667,609.6 -7.359877777800001,57.0109305556,609.6 -7.356827777800001,57.0197555556,609.6 + + + + +
+ + EGRU701F BARRA RWY 15 + 570324N 0073025W -
570345N 0072940W -
570303N 0072834W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570242N 0072919W -
570324N 0073025W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.506858333300001,57.0565277778,609.6 -7.4886011111,57.04490583329999,609.6 -7.4847575404,57.04705471100001,609.6 -7.4805738096,57.04900587710001,609.6 -7.476084,57.0507434167,609.6 -7.494330555599999,57.0623611111,609.6 -7.506858333300001,57.0565277778,609.6 + + + + +
+ + EGRU701G BARRA RWY 33 + 565921N 0072247W -
565900N 0072332W -
565941N 0072436W thence anti-clockwise by the arc of a circle radius 2 NM centred on 570122N 0072635W to
570002N 0072351W -
565921N 0072247W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3795888889,56.98913888890001,609.6 -7.3975619444,57.0006344167,609.6 -7.401405478100001,56.9984881114,609.6 -7.4055874261,56.99653947529999,609.6 -7.410073749999999,56.9948043333,609.6 -7.3920916667,56.9833055556,609.6 -7.3795888889,56.98913888890001,609.6 + + + + +
+ + EGRU702A BENBECULA + A circle, 2 NM radius, centred at 572850N 0072150W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3638888889,57.5138144373,609.6 -7.370243523,57.5136380016,609.6 -7.376530614,57.51311056989999,609.6 -7.3826833427,57.512237748,609.6 -7.3886363291,57.5110288122,609.6 -7.3943263326,57.50949661,609.6 -7.3996929278,57.5076574223,609.6 -7.4046791501,57.5055307894,609.6 -7.4092321026,57.5031393019,609.6 -7.4133035183,57.5005083591,609.6 -7.4168502725,57.4976658978,609.6 -7.4198348381,57.49464209439999,609.6 -7.422225680400001,57.4914690423,609.6 -7.423997587400001,57.48818041100001,609.6 -7.4251319309,57.4848110868,609.6 -7.425616858000001,57.4813968027,609.6 -7.425447409,57.4779737584,609.6 -7.424625562800001,57.4745782363,609.6 -7.4231602077,57.47124621719999,609.6 -7.42106704,57.4680129995,609.6 -7.418368390800001,57.46491282560001,609.6 -7.415092983200001,57.4619785206,609.6 -7.4112756225,57.4592411455,609.6 -7.4069568246,57.4567296703,609.6 -7.4021823834,57.4544706685,609.6 -7.397002885499999,57.4524880377,609.6 -7.3914731746,57.450802748,609.6 -7.3856517729,57.4494326221,609.6 -7.3796002648,57.4483921478,609.6 -7.3733826489,57.4476923261,609.6 -7.3670646665,57.4473405559,609.6 -7.360713111299999,57.4473405559,609.6 -7.3543951289,57.4476923261,609.6 -7.348177513000001,57.4483921478,609.6 -7.3421260049,57.4494326221,609.6 -7.3363046032,57.450802748,609.6 -7.3307748923,57.4524880377,609.6 -7.3255953944,57.4544706685,609.6 -7.3208209532,57.4567296703,609.6 -7.3165021552,57.4592411455,609.6 -7.3126847946,57.4619785206,609.6 -7.3094093869,57.46491282560001,609.6 -7.3067107378,57.4680129995,609.6 -7.3046175701,57.47124621719999,609.6 -7.303152215,57.4745782363,609.6 -7.302330368699999,57.4779737584,609.6 -7.3021609198,57.4813968027,609.6 -7.302645846900001,57.4848110868,609.6 -7.3037801904,57.48818041100001,609.6 -7.3055520973,57.4914690423,609.6 -7.307942939700001,57.49464209439999,609.6 -7.3109275052,57.4976658978,609.6 -7.314474259499999,57.5005083591,609.6 -7.3185456752,57.5031393019,609.6 -7.3230986276,57.5055307894,609.6 -7.328084849999999,57.5076574223,609.6 -7.3334514452,57.50949661,609.6 -7.3391414487,57.5110288122,609.6 -7.345094435099999,57.512237748,609.6 -7.351247163800001,57.51311056989999,609.6 -7.357534254800001,57.5136380016,609.6 -7.3638888889,57.5138144373,609.6 + + + + +
+ + EGRU702B BENBECULA RWY 06 + 572652N 0072615W -
572719N 0072649W -
572756N 0072509W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
572730N 0072435W -
572652N 0072615W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.4375166667,57.4478472222,609.6 -7.4096192222,57.45821586110001,609.6 -7.413171273099999,57.46052727600001,609.6 -7.4163226737,57.46300177,609.6 -7.4190477222,57.4656192222,609.6 -7.4469583333,57.4552444444,609.6 -7.4375166667,57.4478472222,609.6 + + + + +
+ + EGRU702C BENBECULA RWY 24 + 573054N 0071710W -
573027N 0071636W -
572944N 0071832W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
573011N 0071906W -
573054N 0071710W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.286077777799999,57.5148805556,609.6 -7.31827175,57.50297872219999,609.6 -7.3147038122,57.5006722278,609.6 -7.3115371197,57.4982018809,609.6 -7.308797416699999,57.4955878333,609.6 -7.2766166667,57.5074833333,609.6 -7.286077777799999,57.5148805556,609.6 + + + + +
+ + EGRU702D BENBECULA RWY 17 + 573147N 0072334W -
573154N 0072235W -
573049N 0072207W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
573043N 0072306W -
573147N 0072334W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.392660055600001,57.52968433329999,609.6 -7.3849875,57.51181438890001,609.6 -7.379665191,57.5127115306,609.6 -7.3742140602,57.5133465673,609.6 -7.3686786111,57.5137143056,609.6 -7.3763938333,57.53170225,609.6 -7.392660055600001,57.52968433329999,609.6 + + + + +
+ + EGRU702E BENBECULA RWY 35 + 572601N 0072004W -
572554N 0072102W -
572651N 0072127W thence anti-clockwise by the arc of a circle radius 2 NM centred on 572850N 0072150W to
572659N 0072028W -
572601N 0072004W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -7.3344309722,57.4336456389,609.6 -7.3412491111,57.4496147778,609.6 -7.3465157972,57.44864127630001,609.6 -7.3519236088,57.4479274827,609.6 -7.3574286111,57.4474791944,609.6 -7.3506536944,57.4316276944,609.6 -7.3344309722,57.4336456389,609.6 + + + + +
+ + EGRU703A INVERNESS + A circle, 2.5 NM radius, centred at 573233N 0040251W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.0475444444,57.5840676082,609.6 -4.0546862389,57.58389006329999,609.6 -4.0617668949,57.5833589483,609.6 -4.0687258029,57.5824788098,609.6 -4.0755034058,57.5812571816,609.6 -4.0820417136,57.5797045197,609.6 -4.088284804,57.577834112,609.6 -4.0941793039,57.5756619633,609.6 -4.0996748488,57.5732066576,609.6 -4.104724515,57.5704891971,609.6 -4.1092852208,57.56753282179999,609.6 -4.1133180947,57.564362809,609.6 -4.1167888052,57.5610062559,609.6 -4.1196678512,57.5574918464,609.6 -4.1219308101,57.55384960519999,609.6 -4.123558541,57.5501106398,609.6 -4.1245373428,57.5463068745,609.6 -4.1248590642,57.54247077670001,609.6 -4.1245211671,57.5386350794,609.6 -4.1235267406,57.53483250240001,609.6 -4.1218844678,57.53109547249999,609.6 -4.1196085452,57.527455848,609.6 -4.1167185551,57.5239446474,609.6 -4.1132392927,57.520591786,609.6 -4.1092005504,57.51742582220001,609.6 -4.1046368596,57.5144737151,609.6 -4.0995871934,57.5117605968,609.6 -4.0940946335,57.5093095592,609.6 -4.0882060019,57.5071414595,609.6 -4.0819714634,57.5052747435,609.6 -4.0754440997,57.50372529050001,609.6 -4.0686794606,57.50250627909999,609.6 -4.0617350944,57.501628076,609.6 -4.0546700632,57.5010981493,609.6 -4.0475444444,57.500921005,609.6 -4.0404188257,57.5010981493,609.6 -4.0333537944,57.501628076,609.6 -4.0264094283,57.50250627909999,609.6 -4.0196447892,57.50372529050001,609.6 -4.0131174255,57.5052747435,609.6 -4.006882887,57.5071414595,609.6 -4.0009942554,57.5093095592,609.6 -3.9955016955,57.5117605968,609.6 -3.9904520293,57.5144737151,609.6 -3.9858883385,57.51742582220001,609.6 -3.9818495962,57.520591786,609.6 -3.9783703338,57.5239446474,609.6 -3.9754803436,57.527455848,609.6 -3.9732044211,57.53109547249999,609.6 -3.971562148299999,57.53483250240001,609.6 -3.9705677217,57.5386350794,609.6 -3.9702298247,57.54247077670001,609.6 -3.9705515461,57.5463068745,609.6 -3.9715303479,57.5501106398,609.6 -3.9731580788,57.55384960519999,609.6 -3.9754210377,57.5574918464,609.6 -3.978300083700001,57.5610062559,609.6 -3.9817707942,57.564362809,609.6 -3.9858036681,57.56753282179999,609.6 -3.990364373899999,57.5704891971,609.6 -3.99541404,57.5732066576,609.6 -4.000909585,57.5756619633,609.6 -4.0068040849,57.577834112,609.6 -4.0130471752,57.5797045197,609.6 -4.0195854831,57.5812571816,609.6 -4.026363086,57.5824788098,609.6 -4.033321994,57.5833589483,609.6 -4.04040265,57.58389006329999,609.6 -4.0475444444,57.5840676082,609.6 + + + + +
+ + EGRU703B INVERNESS RWY 05 + 573017N 0040700W -
573042N 0040739W -
573108N 0040641W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573044N 0040602W -
573017N 0040700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1166388889,57.5047583333,609.6 -4.1004858611,57.51220786110001,609.6 -4.1044062774,57.5143384338,609.6 -4.1080315965,57.5166154193,609.6 -4.1113429444,57.51902700000001,609.6 -4.1274805556,57.5115833333,609.6 -4.1166388889,57.5047583333,609.6 + + + + +
+ + EGRU703C INVERNESS RWY 23 + 573450N 0035839W -
573426N 0035800W -
573357N 0035901W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573422N 0035940W -
573450N 0035839W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9774833333,57.580575,609.6 -3.9945199444,57.5727610833,609.6 -3.990598808,57.57062697550001,609.6 -3.9869746432,57.5683464492,609.6 -3.9836663056,57.5659313889,609.6 -3.9666166667,57.57375,609.6 -3.9774833333,57.580575,609.6 + + + + +
+ + EGRU703D INVERNESS RWY 11 + 573320N 0040829W -
573350N 0040809W -
573337N 0040702W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573307N 0040722W -
573320N 0040829W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -4.1413694444,57.5554416667,609.6 -4.1228588611,57.5519122778,609.6 -4.1214032257,57.55480654239999,609.6 -4.119563074,57.5576368626,609.6 -4.1173478889,57.5603885,609.6 -4.1357638889,57.5639,609.6 -4.1413694444,57.5554416667,609.6 + + + + +
+ + EGRU703E INVERNESS RWY 29 + 573154N 0035803W -
573124N 0035823W -
573127N 0035841W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 573233N 0040251W to
573158N 0035821W -
573154N 0035803W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.9673888889,57.5316694444,609.6 -3.9724428889,57.53264099999999,609.6 -3.9739612196,57.5297563839,609.6 -3.975861807899999,57.52693809669999,609.6 -3.9781346944,57.5242007778,609.6 -3.9729861111,57.5232111111,609.6 -3.9673888889,57.5316694444,609.6 + + + + +
+ + EGRU705A LOSSIEMOUTH + A circle, 2.5 NM radius, centred at 574224N 0032016W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.3378888889,57.7482304105,609.6 -3.3450630202,57.7480528689,609.6 -3.352175735,57.747521764,609.6 -3.3591661478,57.7466416423,609.6 -3.365974431000001,57.74542003760001,609.6 -3.3725423308,57.74386740610001,609.6 -3.3788136709,57.7419970354,609.6 -3.3847348362,57.7398249306,609.6 -3.3902552337,57.7373696753,609.6 -3.3953277273,57.73465227200001,609.6 -3.3999090406,57.7316959604,609.6 -3.4039601267,57.72852601749999,609.6 -3.4074464995,57.7251695403,609.6 -3.410338525599999,57.7216552125,609.6 -3.4126116729,57.7180130581,609.6 -3.4142467157,57.71427418439999,609.6 -3.4152298924,57.7104705148,609.6 -3.4155530167,57.7066345159,609.6 -3.415213540499999,57.7027989203,609.6 -3.4142145688,57.6989964465,609.6 -3.4125648257,57.6952595206,609.6 -3.410278573399999,57.69161999969999,609.6 -3.4073754839,57.68810890110001,609.6 -3.4038804661,57.6847561392,609.6 -3.3998234477,57.6815902711,609.6 -3.3952391168,57.6786382549,609.6 -3.3901666232,57.6759252214,609.6 -3.3846492432,57.6734742616,609.6 -3.3787340102,57.6713062315,609.6 -3.3724713151,57.6694395761,609.6 -3.365914478600001,57.66789017390001,609.6 -3.3591193005,57.66667120260001,609.6 -3.352143588000001,57.66579302870001,609.6 -3.3450466683,57.66526311970001,609.6 -3.3378888889,57.66508598130001,609.6 -3.3307311095,57.66526311970001,609.6 -3.323634189799999,57.66579302870001,609.6 -3.3166584773,57.66667120260001,609.6 -3.309863299199999,57.66789017390001,609.6 -3.3033064627,57.6694395761,609.6 -3.2970437676,57.6713062315,609.6 -3.2911285346,57.6734742616,609.6 -3.2856111546,57.6759252214,609.6 -3.280538661,57.6786382549,609.6 -3.2759543301,57.6815902711,609.6 -3.2718973117,57.6847561392,609.6 -3.268402293899999,57.68810890110001,609.6 -3.265499204400001,57.69161999969999,609.6 -3.2632129521,57.6952595206,609.6 -3.261563209000001,57.6989964465,609.6 -3.2605642373,57.7027989203,609.6 -3.2602247611,57.7066345159,609.6 -3.2605478854,57.7104705148,609.6 -3.2615310621,57.71427418439999,609.6 -3.263166104899999,57.7180130581,609.6 -3.2654392522,57.7216552125,609.6 -3.2683312783,57.7251695403,609.6 -3.2718176511,57.72852601749999,609.6 -3.2758687372,57.7316959604,609.6 -3.2804500505,57.73465227200001,609.6 -3.285522544,57.7373696753,609.6 -3.2910429416,57.7398249306,609.6 -3.2969641068,57.7419970354,609.6 -3.303235447,57.74386740610001,609.6 -3.3098033468,57.74542003760001,609.6 -3.3166116299,57.7466416423,609.6 -3.3236020428,57.747521764,609.6 -3.3307147576,57.7480528689,609.6 -3.3378888889,57.7482304105,609.6 + + + + +
+ + EGRU705B LOSSIEMOUTH RWY 05 + 573945N 0032419W -
574007N 0032502W -
574048N 0032350W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574025N 0032307W -
573945N 0032419W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.4052303889,57.66239622219999,609.6 -3.3851451111,57.6736762778,609.6 -3.3894605228,57.6755851141,609.6 -3.3935083929,57.67765548039999,609.6 -3.3972676667,57.6798766389,609.6 -3.4173429722,57.6686000833,609.6 -3.4052303889,57.66239622219999,609.6 + + + + +
+ + EGRU705C LOSSIEMOUTH RWY 23 + 574503N 0031614W -
574441N 0031530W -
574400N 0031642W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574423N 0031726W -
574503N 0031614W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2704251389,57.7508905278,609.6 -3.2905774444,57.7396351944,609.6 -3.2862578363,57.7377241466,609.6 -3.2822074459,57.7356514462,609.6 -3.2784473611,57.7334278889,609.6 -3.2582850556,57.74468675,609.6 -3.2704251389,57.7508905278,609.6 + + + + +
+ + EGRU705D LOSSIEMOUTH RWY 10 + 574228N 0032535W -
574300N 0032529W -
574258N 0032449W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574225N 0032456W -
574228N 0032535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.426483277800001,57.7077121111,609.6 -3.4155498889,57.7070576667,609.6 -3.4152973401,57.7100528307,609.6 -3.4146420388,57.7130304583,609.6 -3.4135873056,57.7159750556,609.6 -3.4245959444,57.716634,609.6 -3.426483277800001,57.7077121111,609.6 + + + + +
+ + EGRU705E LOSSIEMOUTH RWY 28 + 574217N 0031343W -
574145N 0031350W -
574152N 0031543W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 574224N 0032016W to
574224N 0031537W -
574217N 0031343W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.2287245833,57.7047635833,609.6 -3.2602247222,57.70669352779999,609.6 -3.260425149,57.70369724730001,609.6 -3.2610283953,57.70071648859999,609.6 -3.2620312222,57.69776675,609.6 -3.2306113056,57.6958416944,609.6 -3.2287245833,57.7047635833,609.6 + + + + +
+ + EGRU706A ABERDEEN/DYCE + A circle, 2.5 NM radius, centred at 571209N 0021153W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1980555556,57.2440754236,609.6 -2.2051314822,57.2438978716,609.6 -2.2121468371,57.2433667355,609.6 -2.2190415719,57.24248656180001,609.6 -2.2257566814,57.2412648843,609.6 -2.2322347123,57.23971215899999,609.6 -2.2384202596,57.2378416738,609.6 -2.2442604437,57.2356694335,609.6 -2.249705365,57.23321402219999,609.6 -2.2547085326,57.2304964423,609.6 -2.2592272616,57.2275399342,609.6 -2.2632230376,57.22436977550001,609.6 -2.266661844,57.221013064,609.6 -2.2695144494,57.2174984844,609.6 -2.2717566538,57.2138560622,609.6 -2.2733694897,57.2101169061,609.6 -2.2743393788,57.2063129417,609.6 -2.2746582417,57.2024766378,609.6 -2.2743235599,57.1986407293,609.6 -2.2733383906,57.19483793769999,609.6 -2.2717113336,57.1911006919,609.6 -2.2694564514,57.18746085240001,609.6 -2.2665931431,57.18394943980001,609.6 -2.2631459735,57.180596372,609.6 -2.2591444585,57.1774302095,609.6 -2.2546228104,57.174477914,609.6 -2.2496196428,57.1717646198,609.6 -2.2441776406,57.1693134211,609.6 -2.2383431954,57.1671451771,609.6 -2.2321660113,57.1652783355,609.6 -2.2256986832,57.1637287773,609.6 -2.2189962516,57.1625096825,609.6 -2.2121157379,57.1616314191,609.6 -2.2051156633,57.1611014558,609.6 -2.1980555556,57.1609242992,609.6 -2.1909954478,57.1611014558,609.6 -2.1839953732,57.1616314191,609.6 -2.1771148595,57.1625096825,609.6 -2.1704124279,57.1637287773,609.6 -2.1639450998,57.1652783355,609.6 -2.1577679157,57.1671451771,609.6 -2.1519334705,57.1693134211,609.6 -2.1464914683,57.1717646198,609.6 -2.1414883007,57.174477914,609.6 -2.1369666526,57.1774302095,609.6 -2.1329651376,57.180596372,609.6 -2.129517968,57.18394943980001,609.6 -2.1266546597,57.18746085240001,609.6 -2.1243997775,57.1911006919,609.6 -2.1227727205,57.19483793769999,609.6 -2.1217875512,57.1986407293,609.6 -2.1214528694,57.2024766378,609.6 -2.1217717323,57.2063129417,609.6 -2.1227416214,57.2101169061,609.6 -2.1243544573,57.2138560622,609.6 -2.1265966617,57.2174984844,609.6 -2.1294492671,57.221013064,609.6 -2.1328880735,57.22436977550001,609.6 -2.1368838495,57.2275399342,609.6 -2.1414025785,57.2304964423,609.6 -2.1464057461,57.23321402219999,609.6 -2.1518506674,57.2356694335,609.6 -2.1576908515,57.2378416738,609.6 -2.1638763988,57.23971215899999,609.6 -2.1703544298,57.2412648843,609.6 -2.1770695392,57.24248656180001,609.6 -2.183964274,57.2433667355,609.6 -2.1909796289,57.2438978716,609.6 -2.1980555556,57.2440754236,609.6 + + + + +
+ + EGRU706B ABERDEEN/DYCE RWY 05 + 571012N 0021521W -
571035N 0021602W -
571046N 0021542W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571021N 0021503W -
571012N 0021521W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2558333333,57.1699,609.6 -2.2509389444,57.1724325,609.6 -2.2547998124,57.1745835737,609.6 -2.2583651059,57.1768803442,609.6 -2.2616161667,57.1793108611,609.6 -2.267225,57.1764083333,609.6 -2.2558333333,57.1699,609.6 + + + + +
+ + EGRU706C ABERDEEN/DYCE RWY 23 + 571428N 0020830W -
571405N 0020749W -
571347N 0020824W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571409N 0020908W -
571428N 0020830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1416416667,57.2412277778,609.6 -2.1521781389,57.2358029722,609.6 -2.1478649411,57.2339182045,609.6 -2.143814412,57.2318693419,609.6 -2.1400476944,57.2296671111,609.6 -2.1302277778,57.2347222222,609.6 -2.1416416667,57.2412277778,609.6 + + + + +
+ + EGRU706D ABERDEEN/DYCE RWY 14 + 571403N 0021541W -
571424N 0021456W -
571410N 0021434W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571349N 0021518W -
571403N 0021541W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.26135,57.2341222222,609.6 -2.2551375556,57.2302386389,609.6 -2.2513035743,57.2323996757,609.6 -2.2471918743,57.23440507859999,609.6 -2.2428238611,57.2362443889,609.6 -2.2488305556,57.24,609.6 -2.26135,57.2341222222,609.6 + + + + +
+ + EGRU706E ABERDEEN/DYCE RWY 32 + 571005N 0020803W -
570944N 0020848W -
571004N 0020920W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571025N 0020835W -
571005N 0020803W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.13425,57.1681777778,609.6 -2.1429397222,57.1736382222,609.6 -2.1469152275,57.1715566524,609.6 -2.1511562433,57.1696360549,609.6 -2.1556406944,57.1678863889,609.6 -2.1467444444,57.1622972222,609.6 -2.13425,57.1681777778,609.6 + + + + +
+ + EGRU706F ABERDEEN/DYCE RWY 16 + 571502N 0021434W -
571514N 0021338W -
571433N 0021308W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
571421N 0021403W -
571502N 0021434W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.2426722222,57.2505722222,609.6 -2.2342207778,57.2391555278,609.6 -2.2292543468,57.2404748588,609.6 -2.2241251251,57.2415964682,609.6 -2.2188598611,57.2425145,609.6 -2.2272916667,57.2539111111,609.6 -2.2426722222,57.2505722222,609.6 + + + + +
+ + EGRU706G ABERDEEN/DYCE RWY 34 + 570915N 0020914W -
570903N 0021009W -
570945N 0021039W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
570957N 0020944W -
570915N 0020914W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1537638889,57.1542722222,609.6 -2.1622190556,57.16575958329999,609.6 -2.1671869666,57.1644531612,609.6 -2.1723149548,57.1633444667,609.6 -2.1775764167,57.16243925000001,609.6 -2.1691027778,57.15093333330001,609.6 -2.1537638889,57.1542722222,609.6 + + + + +
+ + EGRU706I ABERDEEN/DYCE RWY 36 + 570935N 0021131W -
570935N 0021231W -
570941N 0021231W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 571209N 0021153W to
570940N 0021131W -
570935N 0021131W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.1920326944,57.1597811944,609.6 -2.1920731667,57.1610514167,609.6 -2.1975928553,57.1609250685,609.6 -2.2031149457,57.1610151918,609.6 -2.20861075,57.1613213333,609.6 -2.2085559444,57.1596245,609.6 -2.1920326944,57.1597811944,609.6 + + + + +
+ + EGRU801A STORNOWAY + A circle, 2.5 NM radius, centred at 581256N 0061952W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.331066666700001,58.2571659496,609.6 -6.3383433246,58.2569884183,609.6 -6.345557684200001,58.2564573442,609.6 -6.3526479856,58.2555772738,609.6 -6.3595535425,58.2543557411,609.6 -6.3662152656,58.2528032022,609.6 -6.3725761731,58.25093294489999,609.6 -6.3785818819,58.2487609742,609.6 -6.384181075199999,58.2463058737,609.6 -6.3893259432,58.2435886454,609.6 -6.3939725923,58.24063252890001,609.6 -6.3980814193,58.2374628007,609.6 -6.401617448199999,58.2341065568,609.6 -6.404550625800001,58.2305924798,609.6 -6.4068560739,58.2269505926,609.6 -6.4085142969,58.2232120008,609.6 -6.4095113418,58.21940862590001,609.6 -6.4098389112,58.2155729323,609.6 -6.409494426300001,58.21173765,609.6 -6.4084810417,58.2079354948,609.6 -6.4068076117,58.2041988897,609.6 -6.4044886068,58.2005596887,609.6 -6.4015439844,58.19704890570001,609.6 -6.3979990124,58.1936964513,609.6 -6.3938840486,58.1905308793,609.6 -6.3892342779,58.18757914419999,609.6 -6.3840894099,58.1848663732,609.6 -6.3784933381,58.182415654,609.6 -6.3724937661,58.1802478395,609.6 -6.3661418016,58.1783813719,609.6 -6.3594915233,58.1768321269,609.6 -6.352599523299999,58.17561328029999,609.6 -6.3455244289,58.17473519669999,609.6 -6.338326409000001,58.1742053424,609.6 -6.331066666700001,58.1740282223,609.6 -6.3238069243,58.1742053424,609.6 -6.316608904399999,58.17473519669999,609.6 -6.3095338101,58.17561328029999,609.6 -6.30264181,58.1768321269,609.6 -6.2959915317,58.1783813719,609.6 -6.2896395673,58.1802478395,609.6 -6.2836399953,58.182415654,609.6 -6.278043923499999,58.1848663732,609.6 -6.2728990554,58.18757914419999,609.6 -6.2682492848,58.1905308793,609.6 -6.264134320899999,58.1936964513,609.6 -6.2605893489,58.19704890570001,609.6 -6.2576447265,58.2005596887,609.6 -6.2553257217,58.2041988897,609.6 -6.2536522916,58.2079354948,609.6 -6.252638907099999,58.21173765,609.6 -6.252294422099999,58.2155729323,609.6 -6.2526219915,58.21940862590001,609.6 -6.2536190365,58.2232120008,609.6 -6.2552772594,58.2269505926,609.6 -6.257582707500001,58.2305924798,609.6 -6.260515885100001,58.2341065568,609.6 -6.264051914000001,58.2374628007,609.6 -6.268160741,58.24063252890001,609.6 -6.272807390099999,58.2435886454,609.6 -6.277952258200001,58.2463058737,609.6 -6.2835514515,58.2487609742,609.6 -6.2895571602,58.25093294489999,609.6 -6.2959180678,58.2528032022,609.6 -6.3025797908,58.2543557411,609.6 -6.3094853477,58.2555772738,609.6 -6.316575649199999,58.2564573442,609.6 -6.3237900087,58.2569884183,609.6 -6.331066666700001,58.2571659496,609.6 + + + + +
+ + EGRU801B STORNOWAY RWY 06 + 581108N 0062422W -
581136N 0062453W -
581150N 0062406W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581123N 0062333W -
581108N 0062422W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.40615,58.1854555556,609.6 -6.3925569167,58.1896305556,609.6 -6.3959452388,58.19203829709999,609.6 -6.3989963377,58.1945687406,609.6 -6.401694305600001,58.1972087222,609.6 -6.4146805556,58.1932194444,609.6 -6.40615,58.1854555556,609.6 + + + + +
+ + EGRU801C STORNOWAY RWY 24 + 581434N 0061510W -
581406N 0061439W -
581351N 0061528W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581420N 0061557W -
581434N 0061510W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2528305556,58.24278055559999,609.6 -6.2657381389,58.2388406389,609.6 -6.2627313236,58.23629301300001,609.6 -6.2600812359,58.2336375699,609.6 -6.257801638899999,58.2308881667,609.6 -6.2442833333,58.23501388889999,609.6 -6.2528305556,58.24278055559999,609.6 + + + + +
+ + EGRU801D STORNOWAY RWY 18 + 581607N 0062059W -
581610N 0061958W -
581526N 0061949W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581523N 0062050W -
581607N 0062059W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3497055556,58.2686027778,609.6 -6.3473553333,58.25626858330001,609.6 -6.3417523051,58.2567821575,609.6 -6.3360935191,58.2570813209,609.6 -6.3304085,58.2571645,609.6 -6.332752777799999,58.2694972222,609.6 -6.3497055556,58.2686027778,609.6 + + + + +
+ + EGRU801E STORNOWAY RWY 36 + 580941N 0061844W -
580938N 0061945W -
581027N 0061954W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 581256N 0061952W to
581030N 0061853W -
580941N 0061844W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by Stornoway Air Traffic Service unit. For contact details and opening hours see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3122833333,58.1615194444,609.6 -6.3148175,58.1749232778,609.6 -6.3204085528,58.1744109341,609.6 -6.3260548434,58.174112552,609.6 -6.331727111099999,58.17402969439999,609.6 -6.3291861111,58.1606222222,609.6 -6.3122833333,58.1615194444,609.6 + + + + +
+ + EGRU802A WICK + A circle, 2 NM radius, centred at 582732N 0030535W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0930555556,58.4921426198,609.6 -3.0995859271,58.4919662053,609.6 -3.1060468805,58.4914388369,609.6 -3.1123697415,58.49056612049999,609.6 -3.1184873162,58.4893573323,609.6 -3.1243346099,58.4878253192,609.6 -3.1298495226,58.4859863618,609.6 -3.134973512200001,58.4838599997,609.6 -3.1396522186,58.4814688224,609.6 -3.1438360416,58.4788382279,609.6 -3.1474806671,58.47599615130001,609.6 -3.1505475352,58.4729727663,609.6 -3.153004245900001,58.4698001639,609.6 -3.1548248976,58.4665120097,609.6 -3.1559903559,58.4631431864,609.6 -3.156488449699999,58.459729422,609.6 -3.156314091900001,58.4563069112,609.6 -3.1554693256,58.4529119305,609.6 -3.153963294,58.44958045469999,609.6 -3.1518121356,58.4463477753,609.6 -3.1490388059,58.44324812789999,609.6 -3.1456728272,58.44031433060001,609.6 -3.141749971,58.4375774374,609.6 -3.137311874499999,58.4350664112,609.6 -3.1324055973,58.4328078191,609.6 -3.1270831219,58.4308255521,609.6 -3.1214008035,58.429140575,609.6 -3.1154187757,58.4277707055,609.6 -3.1092003171,58.4267304272,609.6 -3.102811186099999,58.4260307381,609.6 -3.096318930799999,58.4256790346,609.6 -3.0897921803,58.4256790346,609.6 -3.083299925,58.4260307381,609.6 -3.0769107941,58.4267304272,609.6 -3.0706923354,58.4277707055,609.6 -3.0647103076,58.429140575,609.6 -3.0590279892,58.4308255521,609.6 -3.053705513800001,58.4328078191,609.6 -3.0487992366,58.4350664112,609.6 -3.0443611401,58.4375774374,609.6 -3.0404382839,58.44031433060001,609.6 -3.0370723052,58.44324812789999,609.6 -3.0342989755,58.4463477753,609.6 -3.0321478171,58.44958045469999,609.6 -3.0306417855,58.4529119305,609.6 -3.029797019200001,58.4563069112,609.6 -3.0296226614,58.459729422,609.6 -3.0301207552,58.4631431864,609.6 -3.0312862136,58.4665120097,609.6 -3.033106865200001,58.4698001639,609.6 -3.0355635759,58.4729727663,609.6 -3.038630444,58.47599615130001,609.6 -3.0422750695,58.4788382279,609.6 -3.0464588925,58.4814688224,609.6 -3.0511375989,58.4838599997,609.6 -3.0562615885,58.4859863618,609.6 -3.0617765012,58.4878253192,609.6 -3.0676237949,58.4893573323,609.6 -3.0737413696,58.49056612049999,609.6 -3.0800642307,58.4914388369,609.6 -3.086525184,58.4919662053,609.6 -3.0930555556,58.4921426198,609.6 + + + + +
+ + EGRU802B WICK RWY 13 + 582909N 0031033W -
582935N 0030956W -
582856N 0030818W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to
582830N 0030855W -
582909N 0031033W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.175763888900001,58.4857583333,609.6 -3.148531222199999,58.47504255560001,609.6 -3.1455271826,58.4775976674,609.6 -3.1420951993,58.48000044259999,609.6 -3.1382631667,58.4822312778,609.6 -3.16545,58.4929305556,609.6 -3.175763888900001,58.4857583333,609.6 + + + + +
+ + EGRU802C WICK RWY 31 + 582555N 0030040W -
582529N 0030117W -
582608N 0030253W thence anti-clockwise by the arc of a circle radius 2 NM centred on 582732N 0030535W to
582633N 0030216W -
582555N 0030040W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -3.0110833333,58.43201666669999,609.6 -3.0377739167,58.4425773056,609.6 -3.0408048412,58.4400322635,609.6 -3.0442604972,58.4376407495,609.6 -3.048112694399999,58.4354221944,609.6 -3.021375,58.4248444444,609.6 -3.0110833333,58.43201666669999,609.6 + + + + +
+ + EGRU803A KIRKWALL + A circle, 2 NM radius, centred at 585729N 0025402W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9004805556,58.9912650259,609.6 -2.9071051505,58.9910886218,609.6 -2.9136593217,58.99056128489999,609.6 -2.9200734005,58.9896886208,609.6 -2.9262792201,58.9884799056,609.6 -2.9322108453,58.9869479864,609.6 -2.9378052781,58.9851091435,609.6 -2.943003130800001,58.98298291610001,609.6 -2.9477492585,58.9805918934,609.6 -2.9519933464,58.97796147259999,609.6 -2.9556904427,58.9751195881,609.6 -2.958801434000001,58.9720964125,609.6 -2.9612934561,58.9689240353,609.6 -2.9631402382,58.9656361206,609.6 -2.9643223745,58.96226754890001,609.6 -2.9648275234,58.958854046,609.6 -2.9646505297,58.9554318039,609.6 -2.9637934711,58.9520370964,609.6 -2.962265627799999,58.9487058948,609.6 -2.9600833753,58.9454734876,609.6 -2.9572700039,58.9423741067,609.6 -2.9538554649,58.93944056660001,609.6 -2.9498760475,58.9367039177,609.6 -2.9453739904,58.9341931194,609.6 -2.940397031699999,58.9319347351,609.6 -2.9349979022,58.9299526531,609.6 -2.9292337674,58.9282678349,609.6 -2.9231656248,58.9268980957,609.6 -2.9168576612,58.9258579171,609.6 -2.9103765784,58.92515829529999,609.6 -2.9037908931,58.9248066258,609.6 -2.897170218,58.9248066258,609.6 -2.8905845327,58.92515829529999,609.6 -2.8841034499,58.9258579171,609.6 -2.8777954863,58.9268980957,609.6 -2.8717273437,58.9282678349,609.6 -2.8659632089,58.9299526531,609.6 -2.8605640794,58.9319347351,609.6 -2.8555871207,58.9341931194,609.6 -2.8510850636,58.9367039177,609.6 -2.8471056462,58.93944056660001,609.6 -2.8436911072,58.9423741067,609.6 -2.8408777358,58.9454734876,609.6 -2.8386954833,58.9487058948,609.6 -2.83716764,58.9520370964,609.6 -2.8363105814,58.9554318039,609.6 -2.8361335877,58.958854046,609.6 -2.8366387366,58.96226754890001,609.6 -2.8378208729,58.9656361206,609.6 -2.839667655,58.9689240353,609.6 -2.8421596771,58.9720964125,609.6 -2.8452706684,58.9751195881,609.6 -2.8489677647,58.97796147259999,609.6 -2.853211852599999,58.9805918934,609.6 -2.8579579804,58.98298291610001,609.6 -2.863155833,58.9851091435,609.6 -2.8687502658,58.9869479864,609.6 -2.874681890999999,58.9884799056,609.6 -2.8808877106,58.9896886208,609.6 -2.8873017895,58.99056128489999,609.6 -2.8938559607,58.9910886218,609.6 -2.9004805556,58.9912650259,609.6 + + + + +
+ + EGRU803B KIRKWALL RWY 09 + 585704N 0025947W -
585737N 0025950W -
585740N 0025753W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585707N 0025750W -
585704N 0025947W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9965222222,58.9512361111,609.6 -2.9637882778,58.9520225,609.6 -2.964578600499999,58.95499465839999,609.6 -2.9648472588,58.9579915212,609.6 -2.9645919444,58.9609886944,609.6 -2.997305555600001,58.9602027778,609.6 -2.9965222222,58.9512361111,609.6 + + + + +
+ + EGRU803C KIRKWALL RWY 27 + 585753N 0024808W -
585721N 0024806W -
585718N 0025011W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585750N 0025014W -
585753N 0024808W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8023416667,58.9647638889,609.6 -2.8371498056,58.9639711944,609.6 -2.8363708043,58.9609981919,609.6 -2.836113826,58.9580010211,609.6 -2.8363808333,58.9550040833,609.6 -2.8015527778,58.9557972222,609.6 -2.8023416667,58.9647638889,609.6 + + + + +
+ + EGRU803D KIRKWALL RWY 14 + 585932N 0025817W -
585953N 0025729W -
585907N 0025615W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585845N 0025701W -
585932N 0025817W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.9713833333,58.9922083333,609.6 -2.9502969444,58.97907983330001,609.6 -2.9464099969,58.9813176402,609.6 -2.9421470098,58.9833649721,609.6 -2.937542805600001,58.98520505560001,609.6 -2.9579805556,58.9979333333,609.6 -2.9713833333,58.9922083333,609.6 + + + + +
+ + EGRU803E KIRKWALL RWY 32 + 585530N 0025028W -
585509N 0025116W -
585544N 0025211W thence anti-clockwise by the arc of a circle radius 2 NM centred on 585729N 0025402W to
585603N 0025121W -
585530N 0025028W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by ATC. ATC must be contacted during operational hours with a minimum of 24 hours notice provided prior to the unmanned aircraft flight within the FRZ. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.8410083333,58.9249138889,609.6 -2.8557253611,58.93412377780001,609.6 -2.8600814518,58.9321339146,609.6 -2.8647667919,58.9303553359,609.6 -2.869743138900001,58.9288025278,609.6 -2.8543805556,58.9191916667,609.6 -2.8410083333,58.9249138889,609.6 + + + + +
+ + EGRU901A TRESCO + A circle, 2 NM radius, centred at 495644N 0061955W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.331898638900001,49.97877589519999,609.6 -6.3372082978,49.9785992755,609.6 -6.3424615574,49.9780712925,609.6 -6.3476026213,49.9771975541,609.6 -6.352576891799999,49.97598734069999,609.6 -6.357331553300001,49.9744535052,609.6 -6.3618161354,49.9726123364,609.6 -6.3659830515,49.9704833849,609.6 -6.3697881047,49.9680892542,609.6 -6.3731909576,49.9654553598,609.6 -6.3761555602,49.9626096581,609.6 -6.3786505308,49.9595823487,609.6 -6.3806494871,49.9564055526,609.6 -6.3821313228,49.9531129705,609.6 -6.383080428300001,49.94973952429999,609.6 -6.383486851199999,49.9463209866,609.6 -6.3833463981,49.94289360019999,609.6 -6.3826606734,49.9394936945,609.6 -6.3814370581,49.9361572996,609.6 -6.3796886263,49.9329197657,609.6 -6.3774340024,49.9298153883,609.6 -6.3746971601,49.9268770461,609.6 -6.371507164800001,49.92413585360001,609.6 -6.367897863500001,49.9216208323,609.6 -6.3639075243,49.9193586054,609.6 -6.3595784308,49.9173731162,609.6 -6.3549564343,49.9156853764,609.6 -6.3500904696,49.9143132447,609.6 -6.3450320383,49.91327123899999,609.6 -6.3398346667,49.91257038329999,609.6 -6.3345533424,49.9122180921,609.6 -6.3292439354,49.9122180921,609.6 -6.323962611,49.91257038329999,609.6 -6.3187652395,49.91327123899999,609.6 -6.3137068082,49.9143132447,609.6 -6.308840843499999,49.9156853764,609.6 -6.304218847,49.9173731162,609.6 -6.299889753499999,49.9193586054,609.6 -6.2958994143,49.9216208323,609.6 -6.2922901129,49.92413585360001,609.6 -6.2891001177,49.9268770461,609.6 -6.2863632754,49.9298153883,609.6 -6.2841086515,49.9329197657,609.6 -6.2823602197,49.9361572996,609.6 -6.2811366044,49.9394936945,609.6 -6.2804508797,49.94289360019999,609.6 -6.2803104265,49.9463209866,609.6 -6.280716849500001,49.94973952429999,609.6 -6.2816659549,49.9531129705,609.6 -6.283147790699999,49.9564055526,609.6 -6.285146747,49.9595823487,609.6 -6.2876417176,49.9626096581,609.6 -6.2906063202,49.9654553598,609.6 -6.294009173099999,49.9680892542,609.6 -6.297814226300001,49.9704833849,609.6 -6.3019811424,49.9726123364,609.6 -6.3064657245,49.9744535052,609.6 -6.311220386,49.97598734069999,609.6 -6.3161946565,49.9771975541,609.6 -6.3213357204,49.9780712925,609.6 -6.32658898,49.9785992755,609.6 -6.331898638900001,49.97877589519999,609.6 + + + + +
+ + EGRU902A SCILLY ISLES/ST MARY'S + A circle, 2 NM radius, centred at 495448N 0061730W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.291758333300001,49.9465871643,609.6 -6.297064453000001,49.94641054380001,609.6 -6.3023142112,49.94588255819999,609.6 -6.3074518487,49.9450088157,609.6 -6.312422804300001,49.9437985963,609.6 -6.3171742977,49.9422647534,609.6 -6.321655892400001,49.9404235756,609.6 -6.3258200333,49.9382946135,609.6 -6.3296225531,49.9359004707,609.6 -6.333023141199999,49.933266563,609.6 -6.3359857716,49.9304208467,609.6 -6.338479083399999,49.9273935215,609.6 -6.3404767119,49.9242167086,609.6 -6.3419575646,49.9209241088,609.6 -6.342906042,49.91755064430001,609.6 -6.3433121985,49.9141320877,609.6 -6.343171842999999,49.9107046821,609.6 -6.3424865789,49.9073047571,609.6 -6.341263782,49.903968343,609.6 -6.3395165174,49.9007307902,609.6 -6.3372633973,49.8976263944,609.6 -6.334528379100001,49.8946880347,609.6 -6.3313405088,49.8919468255,609.6 -6.3277336107,49.8894317889,609.6 -6.3237459277,49.887169548,609.6 -6.319419715,49.8851840465,609.6 -6.3148007936,49.8834962961,609.6 -6.3099380657,49.8821241558,609.6 -6.3048829988,49.8810821435,609.6 -6.2996890837,49.8803812834,609.6 -6.2944112715,49.8800289899,609.6 -6.2891053952,49.8800289899,609.6 -6.283827583,49.8803812834,609.6 -6.2786336679,49.8810821435,609.6 -6.273578601,49.8821241558,609.6 -6.268715873,49.8834962961,609.6 -6.2640969517,49.8851840465,609.6 -6.259770739,49.887169548,609.6 -6.2557830559,49.8894317889,609.6 -6.2521761579,49.8919468255,609.6 -6.2489882876,49.8946880347,609.6 -6.2462532693,49.8976263944,609.6 -6.2440001492,49.9007307902,609.6 -6.242252884699999,49.903968343,609.6 -6.241030087699999,49.9073047571,609.6 -6.240344823599999,49.9107046821,609.6 -6.2402044682,49.9141320877,609.6 -6.240610624600001,49.91755064430001,609.6 -6.2415591021,49.9209241088,609.6 -6.2430399548,49.9242167086,609.6 -6.245037583199999,49.9273935215,609.6 -6.2475308951,49.9304208467,609.6 -6.2504935255,49.933266563,609.6 -6.253894113600001,49.9359004707,609.6 -6.257696633300001,49.9382946135,609.6 -6.261860774300001,49.9404235756,609.6 -6.2663423689,49.9422647534,609.6 -6.271093862300001,49.9437985963,609.6 -6.276064818000001,49.9450088157,609.6 -6.281202455399999,49.94588255819999,609.6 -6.286452213600001,49.94641054380001,609.6 -6.291758333300001,49.9465871643,609.6 + + + + +
+ + EGRU902B SCILLY ISLES/ST MARY'S RWY 09 + 495423N 0062152W -
495456N 0062155W -
495458N 0062035W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495426N 0062033W -
495423N 0062152W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.3645694444,49.9064916667,609.6 -6.34246425,49.9072264167,609.6 -6.343105279199999,49.9102031456,609.6 -6.343328192399999,49.91320507210001,609.6 -6.343131083300001,49.91620775,609.6 -6.3652722222,49.91547222219999,609.6 -6.3645694444,49.9064916667,609.6 + + + + +
+ + EGRU902C SCILLY ISLES/ST MARY'S RWY 27 + 495513N 0061309W -
495441N 0061307W -
495438N 0061425W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495510N 0061428W -
495513N 0061309W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2192583333,49.9202444444,609.6 -6.2411032222,49.9195422222,609.6 -6.2404376283,49.91656837119999,609.6 -6.2401899616,49.9135678841,609.6 -6.2403621389,49.91056519440001,609.6 -6.2185527778,49.9112666667,609.6 -6.2192583333,49.9202444444,609.6 + + + + +
+ + EGRU902D SCILLY ISLES/ST MARY'S RWY 14 + 495647N 0062042W -
495709N 0062004W -
495629N 0061911W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495607N 0061949W -
495647N 0062042W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.345122222200001,49.946525,609.6 -6.330323583299999,49.9354010833,609.6 -6.3270783713,49.93755607170001,609.6 -6.3235450932,49.9395133576,609.6 -6.3197525278,49.9412569722,609.6 -6.3345444444,49.9523777778,609.6 -6.345122222200001,49.946525,609.6 + + + + +
+ + EGRU902E SCILLY ISLES/ST MARY'S RWY 32 + 495248N 0061419W -
495227N 0061457W -
495307N 0061550W thence anti-clockwise by the arc of a circle radius 2 NM centred on 495448N 0061730W to
495328N 0061512W -
495248N 0061419W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -6.2384777778,49.8800277778,609.6 -6.2532298056,49.8911571944,609.6 -6.2564752205,49.8890044172,609.6 -6.260007513899999,49.88704931070001,609.6 -6.2637979444,49.8853077778,609.6 -6.2490388889,49.87417499999999,609.6 -6.2384777778,49.8800277778,609.6 + + + + +
+ + EGRU903A EDAY + A circle, 2 NM radius, centred at 591125N 0024621W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.7724055556,59.2236221598,609.6 -2.7790751247,59.22344576049999,609.6 -2.7856737902,59.2229184379,609.6 -2.7921314086,59.2220457978,609.6 -2.7983793486,59.2208371162,609.6 -2.8043512262,59.2193052401,609.6 -2.8099836148,59.2174664497,609.6 -2.8152167228,59.21534028420001,609.6 -2.8199950311,59.2129493325,609.6 -2.824267883600001,59.2103189917,609.6 -2.8279900241,59.2074771956,609.6 -2.831122075,59.2044541165,609.6 -2.8336309507,59.20128184319999,609.6 -2.835490204,59.19799403889999,609.6 -2.8366802999,59.1946255834,609.6 -2.8371888152,59.19121220139999,609.6 -2.8370105624,59.1877900836,609.6 -2.8361476357,59.18439550250001,609.6 -2.8346093806,59.181064428,609.6 -2.832412286,59.1778321468,609.6 -2.8295798019,59.1747328895,609.6 -2.8261420844,59.1717994687,609.6 -2.8221356698,59.1690629331,609.6 -2.8176030839,59.1665522406,609.6 -2.812592388700001,59.16429395290001,609.6 -2.8071566721,59.1623119567,609.6 -2.8013534865,59.16062721239999,609.6 -2.7952442416,59.1592575338,609.6 -2.7888935577,59.15821740150001,609.6 -2.7823685869,59.1575178111,609.6 -2.7757383079,59.1571661574,609.6 -2.7690728032,59.1571661574,609.6 -2.7624425242,59.1575178111,609.6 -2.7559175534,59.15821740150001,609.6 -2.7495668695,59.1592575338,609.6 -2.7434576246,59.16062721239999,609.6 -2.737654439,59.1623119567,609.6 -2.7322187224,59.16429395290001,609.6 -2.7272080272,59.1665522406,609.6 -2.7226754413,59.1690629331,609.6 -2.7186690267,59.1717994687,609.6 -2.7152313092,59.1747328895,609.6 -2.7123988252,59.1778321468,609.6 -2.7102017305,59.181064428,609.6 -2.7086634754,59.18439550250001,609.6 -2.7078005487,59.1877900836,609.6 -2.7076222959,59.19121220139999,609.6 -2.7081308112,59.1946255834,609.6 -2.7093209071,59.19799403889999,609.6 -2.7111801604,59.20128184319999,609.6 -2.7136890362,59.2044541165,609.6 -2.716821087,59.2074771956,609.6 -2.7205432276,59.2103189917,609.6 -2.72481608,59.2129493325,609.6 -2.7295943883,59.21534028420001,609.6 -2.7348274963,59.2174664497,609.6 -2.7404598849,59.2193052401,609.6 -2.7464317625,59.2208371162,609.6 -2.7526797025,59.2220457978,609.6 -2.7591373209,59.2229184379,609.6 -2.7657359864,59.22344576049999,609.6 -2.7724055556,59.2236221598,609.6 + + + + +
+ + EGRU904A STRONSAY + A circle, 2 NM radius, centred at 590919N 0023830W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.6415277778,59.1885278961,609.6 -2.648190508,59.1883514961,609.6 -2.6547824075,59.1878241714,609.6 -2.6612334051,59.1869515277,609.6 -2.6674749401,59.18574284110001,609.6 -2.6734406968,59.1842109585,609.6 -2.6790673137,59.1823721602,609.6 -2.6842950607,59.1802459854,609.6 -2.6890684755,59.177855023,609.6 -2.6933369539,59.1752246701,609.6 -2.6970552861,59.1723828607,609.6 -2.7001841346,59.1693597671,609.6 -2.7026904476,59.1661874781,609.6 -2.7045478046,59.1628996572,609.6 -2.7057366901,59.1595311842,609.6 -2.7062446936,59.156117784,609.6 -2.7060666323,59.1526956474,609.6 -2.7052045979,59.1493010472,609.6 -2.7036679261,59.1459699536,609.6 -2.7014730884,59.14273765339999,609.6 -2.6986435108,59.13963837739999,609.6 -2.6952093178,59.1367049386,609.6 -2.6912070085,59.1339683859,609.6 -2.686679065,59.1314576774,609.6 -2.6816734998,59.1291993752,609.6 -2.6762433467,59.12721736610001,609.6 -2.6704460993,59.1255326105,609.6 -2.6643431045,59.1241629228,609.6 -2.6579989168,59.1231227835,609.6 -2.6514806197,59.12242318840001,609.6 -2.6448571217,59.12207153229999,609.6 -2.6381984339,59.12207153229999,609.6 -2.6315749359,59.12242318840001,609.6 -2.6250566388,59.1231227835,609.6 -2.618712451,59.1241629228,609.6 -2.6126094562,59.1255326105,609.6 -2.6068122088,59.12721736610001,609.6 -2.6013820557,59.1291993752,609.6 -2.5963764906,59.1314576774,609.6 -2.591848547,59.1339683859,609.6 -2.5878462377,59.1367049386,609.6 -2.5844120448,59.13963837739999,609.6 -2.5815824671,59.14273765339999,609.6 -2.5793876295,59.1459699536,609.6 -2.5778509576,59.1493010472,609.6 -2.5769889233,59.1526956474,609.6 -2.576810862,59.156117784,609.6 -2.5773188654,59.1595311842,609.6 -2.578507751,59.1628996572,609.6 -2.5803651079,59.1661874781,609.6 -2.5828714209,59.1693597671,609.6 -2.5860002694,59.1723828607,609.6 -2.5897186017,59.1752246701,609.6 -2.5939870801,59.177855023,609.6 -2.5987604949,59.1802459854,609.6 -2.6039882418,59.1823721602,609.6 -2.6096148588,59.1842109585,609.6 -2.6155806155,59.18574284110001,609.6 -2.6218221505,59.1869515277,609.6 -2.6282731481,59.1878241714,609.6 -2.6348650476,59.1883514961,609.6 -2.6415277778,59.1885278961,609.6 + + + + +
+ + EGRU905A SANDAY + A circle, 2 NM radius, centred at 591501N 0023430W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.575,59.28341907410001,609.6 -2.5816812603,59.2832426761,609.6 -2.5882914921,59.2827153572,609.6 -2.5947604287,59.2818427233,609.6 -2.601019318,59.2806340502,609.6 -2.6070016592,59.2791021852,609.6 -2.6126439145,59.2772634082,609.6 -2.6178861871,59.2751372585,609.6 -2.6226728607,59.27274632500001,609.6 -2.6269531904,59.27011600469999,609.6 -2.6306818411,59.2672742313,609.6 -2.6338193664,59.2642511769,609.6 -2.6363326231,59.2610789301,609.6 -2.6381951183,59.2577911543,609.6 -2.6393872831,59.2544227286,609.6 -2.6398966734,59.2510093776,609.6 -2.6397180932,59.2475872917,609.6 -2.638853641,59.244192743,609.6 -2.6373126792,59.2408617011,609.6 -2.6351117263,59.2376294523,609.6 -2.6322742739,59.2345302267,609.6 -2.628830531,59.2315968366,609.6 -2.6248170985,59.2288603301,609.6 -2.6202765767,59.2263496648,609.6 -2.6152571117,59.224091402,609.6 -2.6098118844,59.22210942789999,609.6 -2.6039985477,59.2204247025,609.6 -2.5978786183,59.2190550394,609.6 -2.5915168294,59.21801491909999,609.6 -2.58498045,59.21731533679999,609.6 -2.578338579,59.2169636871,609.6 -2.571661421,59.2169636871,609.6 -2.56501955,59.21731533679999,609.6 -2.5584831706,59.21801491909999,609.6 -2.5521213817,59.2190550394,609.6 -2.5460014523,59.2204247025,609.6 -2.5401881156,59.22210942789999,609.6 -2.5347428883,59.224091402,609.6 -2.5297234233,59.2263496648,609.6 -2.5251829015,59.2288603301,609.6 -2.521169469,59.2315968366,609.6 -2.5177257261,59.2345302267,609.6 -2.5148882737,59.2376294523,609.6 -2.5126873208,59.2408617011,609.6 -2.511146359,59.244192743,609.6 -2.5102819068,59.2475872917,609.6 -2.5101033266,59.2510093776,609.6 -2.5106127169,59.2544227286,609.6 -2.5118048817,59.2577911543,609.6 -2.5136673769,59.2610789301,609.6 -2.5161806336,59.2642511769,609.6 -2.5193181589,59.2672742313,609.6 -2.5230468096,59.27011600469999,609.6 -2.5273271393,59.27274632500001,609.6 -2.5321138129,59.2751372585,609.6 -2.5373560855,59.2772634082,609.6 -2.5429983408,59.2791021852,609.6 -2.548980682,59.2806340502,609.6 -2.5552395713,59.2818427233,609.6 -2.5617085079,59.2827153572,609.6 -2.5683187397,59.2832426761,609.6 -2.575,59.28341907410001,609.6 + + + + +
+ + EGRU906A NORTH RONALDSAY + A circle, 2 NM radius, centred at 592203N 0022605W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.4346972222,59.4008184708,609.6 -2.4414015769,59.4006420752,609.6 -2.4480346567,59.4001147635,609.6 -2.454525951,59.3992421415,609.6 -2.4608064692,59.39803348529999,609.6 -2.4668094801,59.3965016417,609.6 -2.4724712256,59.3946628911,609.6 -2.4777316019,59.3925367724,609.6 -2.4825348001,59.3901458745,609.6 -2.4868299002,59.38751559430001,609.6 -2.4905714109,59.3846738652,609.6 -2.4937197499,59.3816508592,609.6 -2.4962416607,59.3784786646,609.6 -2.4981105595,59.3751909442,609.6 -2.4993068112,59.37182257689999,609.6 -2.4998179299,59.36840928670001,609.6 -2.4996387027,59.3649872634,609.6 -2.4987712369,59.3615927783,609.6 -2.4972249285,59.35826180039999,609.6 -2.4950163539,59.3550296151,609.6 -2.492169087,59.3519304518,609.6 -2.4887134419,59.3489971217,609.6 -2.4846861463,59.3462606725,609.6 -2.4801299481,59.3437500605,609.6 -2.4750931596,59.3414918463,609.6 -2.4696291451,59.3395099156,609.6 -2.4637957561,59.33782522749999,609.6 -2.457654721,59.336455595,609.6 -2.4512709957,59.33541549810001,609.6 -2.4447120802,59.33471593150001,609.6 -2.438047311,59.33436428990001,609.6 -2.4313471335,59.33436428990001,609.6 -2.4246823642,59.33471593150001,609.6 -2.4181234487,59.33541549810001,609.6 -2.4117397234,59.336455595,609.6 -2.4055986884,59.33782522749999,609.6 -2.3997652994,59.3395099156,609.6 -2.3943012849,59.3414918463,609.6 -2.3892644964,59.3437500605,609.6 -2.3847082982,59.3462606725,609.6 -2.3806810026,59.3489971217,609.6 -2.3772253575,59.3519304518,609.6 -2.3743780906,59.3550296151,609.6 -2.372169516,59.35826180039999,609.6 -2.3706232075,59.3615927783,609.6 -2.3697557417,59.3649872634,609.6 -2.3695765146,59.36840928670001,609.6 -2.3700876332,59.37182257689999,609.6 -2.3712838849,59.3751909442,609.6 -2.3731527837,59.3784786646,609.6 -2.3756746945,59.3816508592,609.6 -2.3788230336,59.3846738652,609.6 -2.3825645443,59.38751559430001,609.6 -2.3868596444,59.3901458745,609.6 -2.3916628426,59.3925367724,609.6 -2.3969232188,59.3946628911,609.6 -2.4025849643,59.3965016417,609.6 -2.4085879752,59.39803348529999,609.6 -2.4148684935,59.3992421415,609.6 -2.4213597877,59.4001147635,609.6 -2.4279928675,59.4006420752,609.6 -2.4346972222,59.4008184708,609.6 + + + + +
+ + EGRU907A FAIR ISLE + A circle, 2 NM radius, centred at 593205N 0013743W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.6285111111,59.5679759474,609.6 -1.6352486751,59.5677995552,609.6 -1.6419146096,59.56727225369999,609.6 -1.6484380536,59.56639964869999,609.6 -1.6547496737,59.56519101619999,609.6 -1.660782407,59.5636592032,609.6 -1.6664721789,59.5618204898,609.6 -1.6717585875,59.55969441500001,609.6 -1.6765855474,59.5573035675,609.6 -1.6809018868,59.554673344,609.6 -1.6846618895,59.5518316778,609.6 -1.6878257782,59.5488087405,609.6 -1.6903601329,59.5456366198,609.6 -1.6922382397,59.5423489782,609.6 -1.6934403679,59.53898069379999,609.6 -1.6939539715,59.5355674899,609.6 -1.6937738138,59.5321455553,609.6 -1.6929020143,59.5287511606,609.6 -1.6913480172,59.5254202735,609.6 -1.6891284828,59.5221881786,609.6 -1.6862671028,59.5190891037,609.6 -1.6827943426,59.5161558591,609.6 -1.6787471124,59.5134194912,609.6 -1.674168372,59.510908955,609.6 -1.669106673,59.5086508102,609.6 -1.6636156433,59.5066689411,609.6 -1.6577534201,59.504984306,609.6 -1.6515820362,59.503614717,609.6 -1.6451667673,59.5025746534,609.6 -1.6385754462,59.5018751093,609.6 -1.6318777503,59.501523479,609.6 -1.6251444719,59.501523479,609.6 -1.6184467761,59.5018751093,609.6 -1.6118554549,59.5025746534,609.6 -1.605440186,59.503614717,609.6 -1.5992688021,59.504984306,609.6 -1.5934065789,59.5066689411,609.6 -1.5879155492,59.5086508102,609.6 -1.5828538502,59.510908955,609.6 -1.5782751099,59.5134194912,609.6 -1.5742278797,59.5161558591,609.6 -1.5707551194,59.5190891037,609.6 -1.5678937394,59.5221881786,609.6 -1.565674205,59.5254202735,609.6 -1.5641202079,59.5287511606,609.6 -1.5632484084,59.5321455553,609.6 -1.5630682507,59.5355674899,609.6 -1.5635818543,59.53898069379999,609.6 -1.5647839825,59.5423489782,609.6 -1.5666620893,59.5456366198,609.6 -1.569196444,59.5488087405,609.6 -1.5723603328,59.5518316778,609.6 -1.5761203355,59.554673344,609.6 -1.5804366748,59.5573035675,609.6 -1.5852636348,59.55969441500001,609.6 -1.5905500433,59.5618204898,609.6 -1.5962398152,59.5636592032,609.6 -1.6022725485,59.56519101619999,609.6 -1.6085841686,59.56639964869999,609.6 -1.6151076126,59.56727225369999,609.6 -1.6217735472,59.5677995552,609.6 -1.6285111111,59.5679759474,609.6 + + + + +
+ + EGRU908A SUMBURGH + A circle, 2 NM radius, centred at 595253N 0011738W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2938289167,59.91472354030001,609.6 -1.3006366179,59.914547155,609.6 -1.3073719411,59.9140198744,609.6 -1.3139632846,59.9131473042,609.6 -1.3203405909,59.9119387204,609.6 -1.3264360969,59.91040697,609.6 -1.3321850596,59.908568333,609.6 -1.3375264472,59.9064423484,609.6 -1.3424035907,59.9040516045,609.6 -1.346764786,59.9014214977,609.6 -1.3505638424,59.8985799609,609.6 -1.3537605706,59.8955571648,609.6 -1.3563212053,59.89238519650001,609.6 -1.3582187579,59.8890977171,609.6 -1.3594332958,59.8857296036,609.6 -1.3599521463,59.88231657770001,609.6 -1.3597700222,59.87889482640001,609.6 -1.3588890691,59.8755006183,609.6 -1.3573188329,59.8721699191,609.6 -1.3550761509,59.86893801069999,609.6 -1.3521849641,59.8658391189,609.6 -1.3486760571,59.8629060512,609.6 -1.3445867258,59.8601698514,609.6 -1.3399603776,59.8576594723,609.6 -1.3348460691,59.855401471,609.6 -1.3292979853,59.8534197296,609.6 -1.3233748663,59.8517352043,609.6 -1.317139388,59.85036570540001,609.6 -1.310657502,59.8493257108,609.6 -1.3039977428,59.84862621330001,609.6 -1.2972305088,59.8482746066,609.6 -1.2904273245,59.8482746066,609.6 -1.2836600906,59.84862621330001,609.6 -1.2770003314,59.8493257108,609.6 -1.2705184453,59.85036570540001,609.6 -1.264282967,59.8517352043,609.6 -1.258359848,59.8534197296,609.6 -1.2528117642,59.855401471,609.6 -1.2476974557,59.8576594723,609.6 -1.2430711075,59.8601698514,609.6 -1.2389817762,59.8629060512,609.6 -1.2354728692,59.8658391189,609.6 -1.2325816824,59.86893801069999,609.6 -1.2303390004,59.8721699191,609.6 -1.2287687643,59.8755006183,609.6 -1.2278878111,59.87889482640001,609.6 -1.227705687,59.88231657770001,609.6 -1.2282245375,59.8857296036,609.6 -1.2294390754,59.8890977171,609.6 -1.231336628,59.89238519650001,609.6 -1.2338972627,59.8955571648,609.6 -1.237093991,59.8985799609,609.6 -1.2408930474,59.9014214977,609.6 -1.2452542426,59.9040516045,609.6 -1.2501313861,59.9064423484,609.6 -1.2554727738,59.908568333,609.6 -1.2612217364,59.91040697,609.6 -1.2673172424,59.9119387204,609.6 -1.2736945487,59.9131473042,609.6 -1.2802858923,59.9140198744,609.6 -1.2870212155,59.914547155,609.6 -1.2938289167,59.91472354030001,609.6 + + + + +
+ + EGRU908B SUMBURGH RWY 06 + 595040N 0012125W -
595106N 0012203W -
595137N 0012040W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595114N 0011952W -
595040N 0012125W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3568085833,59.8444108056,609.6 -1.3311036389,59.85401805560001,609.6 -1.3359630795,59.8558562601,609.6 -1.3404666687,59.8579111898,609.6 -1.3445763333,59.8601654722,609.6 -1.3674341667,59.8516208056,609.6 -1.3568085833,59.8444108056,609.6 + + + + +
+ + EGRU908C SUMBURGH RWY 24 + 595429N 0011258W -
595403N 0011220W -
595329N 0011351W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595359N 0011419W -
595429N 0011258W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.2162301667,59.90798866669999,609.6 -1.2384997778,59.89970961110001,609.6 -1.2354006971,59.897077012,609.6 -1.2327967446,59.8943124159,609.6 -1.2307098611,59.89143925,609.6 -1.2055865833,59.9007787222,609.6 -1.2162301667,59.90798866669999,609.6 + + + + +
+ + EGRU908D SUMBURGH RWY 09 + 595217N 0012335W -
595249N 0012342W -
595256N 0012136W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595224N 0012129W -
595217N 0012335W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3929947222,59.87130875,609.6 -1.3579365,59.87331869439999,609.6 -1.3591408487,59.8762570415,609.6 -1.359813575,59.8792380001,609.6 -1.3599490556,59.8822373056,609.6 -1.3949956111,59.88022805560001,609.6 -1.3929947222,59.87130875,609.6 + + + + +
+ + EGRU908E SUMBURGH RWY 27 + 595330N 0011140W -
595258N 0011133W -
595251N 0011340W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595323N 0011347W -
595330N 0011140W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.19437,59.8916009167,609.6 -1.2296873611,59.8896215833,609.6 -1.2284900505,59.8866824629,609.6 -1.2278249785,59.88370106230001,609.6 -1.2276974167,59.88070166670001,609.6 -1.1923684444,59.88268163890001,609.6 -1.19437,59.8916009167,609.6 + + + + +
+ + EGRU908F SUMBURGH RWY 15 + 595450N 0012132W -
595509N 0012041W -
595434N 0011948W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595412N 0012037W -
595450N 0012132W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.3589489444,59.9138691667,609.6 -1.3434973056,59.9034362778,609.6 -1.3393430101,59.9056034287,609.6 -1.3348151617,59.9075729269,609.6 -1.3299508611,59.9093286111,609.6 -1.34459625,59.9192197778,609.6 -1.3589489444,59.9138691667,609.6 + + + + +
+ + EGRU908G SUMBURGH RWY 33 + 595022N 0011337W -
595003N 0011429W -
595104N 0011559W thence anti-clockwise by the arc of a circle radius 2 NM centred on 595253N 0011738W to
595122N 0011504W -
595022N 0011337W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit. ATC must be contacted during opening hours and informed of flights 24 hours in advance of operation. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -1.226986,59.8395753611,609.6 -1.2512414722,59.8560408056,609.6 -1.2559873152,59.8542101142,609.6 -1.2610422146,59.8526025447,609.6 -1.2663648333,59.8512312222,609.6 -1.2413044167,59.8342246667,609.6 -1.226986,59.8395753611,609.6 + + + + +
+ + EGRU909A WESTRAY + A circle, 2 NM radius, centred at 592100N 0025700W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.949875,59.3832852275,609.6 -2.9565758937,59.3831088315,609.6 -2.9632055494,59.3825815187,609.6 -2.969693493,59.381708895,609.6 -2.9759707698,59.38050023620001,609.6 -2.9819706831,59.3789683895,609.6 -2.9876295077,59.37712963489999,609.6 -2.9928871709,59.3750035117,609.6 -2.997687892600001,59.3726126084,609.6 -3.0019807792,59.3699823222,609.6 -3.0057203627,59.3671405865,609.6 -3.0088670811,59.3641175733,609.6 -3.011387694999999,59.36094537089999,609.6 -3.0132556341,59.3576576423,609.6 -3.0144512734,59.35428926630001,609.6 -3.014962133,59.350875967,609.6 -3.014783002799999,59.34745393429999,609.6 -3.0139159887,59.3440594397,609.6 -3.0123704815,59.3407284522,609.6 -3.0101630491,59.3374962575,609.6 -3.0073172531,59.3343970849,609.6 -3.0038633917,59.3314637459,609.6 -2.9998381737,59.3287272881,609.6 -2.9952843248,59.3262166681,609.6 -2.9902501325,59.32395844669999,609.6 -2.9847889335,59.3219765095,609.6 -2.9789585496,59.32029181579999,609.6 -2.9728206775,59.31892217879999,609.6 -2.9664402396,59.3178820784,609.6 -2.9598847015,59.3171825094,609.6 -2.9532233639,59.3168308666,609.6 -2.946526636100001,59.3168308666,609.6 -2.9398652985,59.3171825094,609.6 -2.9333097604,59.3178820784,609.6 -2.9269293225,59.31892217879999,609.6 -2.920791450399999,59.32029181579999,609.6 -2.9149610665,59.3219765095,609.6 -2.9094998675,59.32395844669999,609.6 -2.9044656752,59.3262166681,609.6 -2.8999118263,59.3287272881,609.6 -2.895886608300001,59.3314637459,609.6 -2.8924327469,59.3343970849,609.6 -2.8895869509,59.3374962575,609.6 -2.8873795185,59.3407284522,609.6 -2.8858340113,59.3440594397,609.6 -2.8849669972,59.34745393429999,609.6 -2.884787867,59.350875967,609.6 -2.8852987266,59.35428926630001,609.6 -2.8864943659,59.3576576423,609.6 -2.888362305,59.36094537089999,609.6 -2.8908829189,59.3641175733,609.6 -2.8940296373,59.3671405865,609.6 -2.8977692208,59.3699823222,609.6 -2.9020621074,59.3726126084,609.6 -2.9068628291,59.3750035117,609.6 -2.9121204923,59.37712963489999,609.6 -2.9177793169,59.3789683895,609.6 -2.9237792302,59.38050023620001,609.6 -2.930056507,59.381708895,609.6 -2.9365444506,59.3825815187,609.6 -2.943174106299999,59.3831088315,609.6 -2.949875,59.3832852275,609.6 + + + + +
+ + EGRU910A PAPA WESTRAY + A circle, 2 NM radius, centred at 592103N 0025401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -2.90035,59.3841574452,609.6 -2.9070510658,59.3839810493,609.6 -2.9136808917,59.3834537366,609.6 -2.9201690019,59.38258111289999,609.6 -2.9264464399,59.3813724543,609.6 -2.9324465072,59.37984060769999,609.6 -2.938105477,59.3780018533,609.6 -2.943363275,59.3758757303,609.6 -2.9481641199,59.37348482729999,609.6 -2.9524571166,59.3708545414,609.6 -2.9561967958,59.368012806,609.6 -2.9593435949,59.3649897932,609.6 -2.9618642732,59.3618175912,609.6 -2.9637322601,59.35852986290001,609.6 -2.9649279298,59.3551614874,609.6 -2.9654388023,59.3517481885,609.6 -2.965259667299999,59.3483261563,609.6 -2.9643926307,59.3449316622,609.6 -2.9628470836,59.3416006752,609.6 -2.9606395945,59.338368481,609.6 -2.9577937253,59.33526930879999,609.6 -2.9543397752,59.3323359702,609.6 -2.9503144539,59.3295995128,609.6 -2.945760488199999,59.32708889330001,609.6 -2.940726166800001,59.3248306723,609.6 -2.9352648279,59.3228487353,609.6 -2.9294342945,59.3211640419,609.6 -2.9232962652,59.31979440509999,609.6 -2.9169156639,59.3187543049,609.6 -2.9103599579,59.3180547361,609.6 -2.903698449599999,59.3177030933,609.6 -2.8970015504,59.3177030933,609.6 -2.8903400421,59.3180547361,609.6 -2.883784336100001,59.3187543049,609.6 -2.877403734800001,59.31979440509999,609.6 -2.8712657055,59.3211640419,609.6 -2.8654351721,59.3228487353,609.6 -2.8599738332,59.3248306723,609.6 -2.8549395118,59.32708889330001,609.6 -2.850385546100001,59.3295995128,609.6 -2.8463602248,59.3323359702,609.6 -2.842906274699999,59.33526930879999,609.6 -2.8400604055,59.338368481,609.6 -2.8378529164,59.3416006752,609.6 -2.8363073693,59.3449316622,609.6 -2.8354403327,59.3483261563,609.6 -2.8352611977,59.3517481885,609.6 -2.8357720702,59.3551614874,609.6 -2.8369677399,59.35852986290001,609.6 -2.8388357268,59.3618175912,609.6 -2.8413564051,59.3649897932,609.6 -2.8445032042,59.368012806,609.6 -2.8482428834,59.3708545414,609.6 -2.8525358801,59.37348482729999,609.6 -2.857336725000001,59.3758757303,609.6 -2.862594523,59.3780018533,609.6 -2.868253492800001,59.37984060769999,609.6 -2.8742535601,59.3813724543,609.6 -2.880530998099999,59.38258111289999,609.6 -2.8870191083,59.3834537366,609.6 -2.8936489342,59.3839810493,609.6 -2.90035,59.3841574452,609.6 + + + + +
+ + Basildon University Hospital + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4518516456687849,51.55800083830794,58.08521858368528 + + + + Basildon University Hospital Accident and ... + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4515649145776108,51.55862862589095,63.25143581313333 + + + + Mulberry Assessment Centre, Basildon Hospital + + 0.4521352198389494 + 51.5591080503393 + 53.94959600323294 + 53.28182780950215 + 59.9490031744898 + 35 + 990.0405204026902 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4543600102226297,51.55892826898683,61.12414806775797 + + + + Basildon Mental Health Unity + + 0.4521352191627104 + 51.5591080503393 + 53.94959600323294 + 53.28182780882707 + 59.94900317415277 + 35 + 990.0404276922927 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4504371056189932,51.55704006258427,58.6390360083163 + + + + Basildon Hospital Simulation Suite + + 0.4521352191627104 + 51.5591080503393 + 53.94959600323294 + 53.28182780882707 + 59.94900317415277 + 35 + 990.0404276922927 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4483682821085228,51.55806422210383,63.90305654267409 + + + + Fryerns Medical Centre + + 0.4752487883464585 + 51.57345754883367 + 36.16638769277598 + 53.29440376545357 + 59.96137223993925 + 35 + 2579.139101160108 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4898574326064499,51.57853506709266,17.93325067593601 + + + + Murree Medical Centre + + 0.4752487883464585 + 51.57345754883367 + 36.16638769277598 + 53.29440376545357 + 59.96137223993925 + 35 + 2579.139101160108 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4813540951236296,51.57658601871081,32.47146360214328 + + + + St Peter's Hospital + + 0.6771628259292584 + 51.72855213684512 + 22.87229294006159 + 53.59273614142136 + 59.96772415652145 + 35 + 3395.186773824971 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6715336638568048,51.73008053466475,37.51985194938187 + + + + Halstead Hospital + + 0.6245231935558504 + 51.93606495933507 + 76.48619882270123 + 53.37055133585243 + 59.97207446579549 + 35 + 3954.119959588861 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6379421359890148,51.94822718909322,56.15721830449306 + + + + Braintree Community Hospital + + 0.5430527758506498 + 51.87377121150501 + 62.36813868970528 + 53.41759414375864 + 59.98836798134744 + 35 + 6047.409481286305 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.5404253949175911,51.87984317552653,73.81262799233804 + + + + The Diamond Jubilee Maternity Unit + + -0.2124631480823957 + 51.92494721624239 + 104.0976233919343 + 52.9758961558414 + 59.95105134000257 + 35 + 1253.18674576105 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2129362336881956,51.92518764307876,110.0953336152518 + + + + Lister Hospital + + -0.212468574646324 + 51.92494469212421 + 104.3672773546513 + 52.97589188408732 + 59.9510471482962 + 35 + 1252.648283772724 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2135874989268621,51.92479263064346,101.8568048294726 + + + + HUC - Out of Hours GP + + -0.2128663374478001 + 51.92409839224334 + 103.9704651502259 + 52.97090875999339 + 59.94615536733049 + 35 + 624.1757174913073 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2124606678525842,51.92399879325587,104.0006496808524 + + + + Lister Hospital Emergency Department + + -0.2130003658019952 + 51.92379570577413 + 103.6350906758858 + 52.96867367002447 + 59.94400554001695 + 35 + 347.9761926599167 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2131164264773755,51.92347331413398,105.8779680833839 + + + + Nuffield Health The Holly Hospital + + 0.04585464223887392 + 51.6273689474134 + 38.71012647809278 + 52.6782196690201 + 51.39213189060273 + 35 + 7140.686088680523 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.03206290779532616,51.62442607065198,89.33019685902229 + + + + Queen's Hospital + + 0.1776221298435821 + 51.568919431133 + 18.68235898810621 + 52.70128481440929 + 51.35174310452052 + 35 + 1389.46064643198 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1807244269402526,51.56881358641575,12.94033315619186 + + + + Westland Medical Centre + + 0.2228178699336936 + 51.56316393681531 + 24.91386746893415 + 52.71510149753455 + 51.34380426939081 + 35 + 259.002024237634 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.222502152998362,51.56324992662208,36.43244775473649 + + + + St Helier Hospital + + -0.1836714323780464 + 51.37943893083443 + 64.97684684371181 + 52.53141226490936 + 51.3474330441067 + 35 + 775.7306094201341 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1840303861177935,51.38066504383517,54.62768807727091 + + + + Royal Marsden Hospital Sutton + + -0.1822717128616835 + 51.35589791498172 + 82.72412170132267 + 0 + 0 + 35 + 10106.34484948707 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1905873927941104,51.34350718522376,113.8340941248334 + + + + Purley War Memorial Hospital + + -0.1255512268054504 + 51.34715829880357 + 94.09292593156277 + 0 + 0 + 35 + 7615.273579903878 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.114544072907744,51.34062051573004,67.32324151583683 + + + + Croydon University Hospital + + -0.1282538571809755 + 51.36920404406935 + 33.23487247684645 + 0 + 0 + 35 + 14722.70630323096 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1102925394917569,51.389918395302,41.05019751627281 + + + + Shirley Oaks Hospital + + -0.0616817930399749 + 51.38073877031137 + 60.35530623298428 + 0 + 0 + 35 + 3182.032219815302 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.05634685139080654,51.38221664329148,60.984781076469 + + + + Croydon Ambulance Station + + -0.06251225601590193 + 51.38016865443452 + 60.88740413407257 + 0 + 0 + 35 + 4138.098180682864 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.06024907709478369,51.37797845256939,66.88672959253627 + + + + The Sloane Hospital + + -0.003827308058029777 + 51.408502944809 + 53.75774730066906 + 0 + 0 + 35 + 4994.659184503835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.004566234546706421,51.40833204621094,52.72717876895458 + + + + Thorridon Road Medical Practice + + 0.02233089355464069 + 51.42543834363784 + 62.51135261638856 + 0 + 0 + 35 + 7836.865521763684 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.002054664159771846,51.440107077768,40.88826480158826 + + + + Oakview Family Practice + + 0.02130458356131015 + 51.43560043559513 + 50.07093654013592 + 0 + 0 + 35 + 8053.896853752667 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.008003161007248405,51.42990810684785,61.19208890472149 + + + + The Links Medical Practice + + 0.02130458356131015 + 51.43560043559513 + 50.07093654013592 + 0 + 0 + 35 + 8053.896853752667 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.04154414921016782,51.42766668244509,70.41641735557513 + + + + Sidcup Medical Centre + + 0.1092621727262832 + 51.44660865553494 + 31.79733927167157 + 0 + 0 + 35 + 8072.170443929499 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.105179783005751,51.44519015710028,31.82578746927528 + + + + Lyndhurst Medical Centre + + 0.1562897017726139 + 51.45661682961929 + 52.3107859491431 + 0 + 0 + 35 + 6261.262700851077 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.158829036674426,51.46116796457344,56.48601887654782 + + + + Erith and District Hospital + + 0.1646645982058437 + 51.47784355884365 + 39.09017403376667 + 0 + 0 + 35 + 4587.136169738369 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1673704454554059,51.47691812682567,43.98073424517573 + + + + Berwick Surgery + + 0.217899522818934 + 51.52204207630847 + 5.612937055866576 + 0 + 0 + 35 + 5203.539418349974 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.2141959818805272,51.52672713573709,11.57048005941898 + + + + Orsett Hospital + + 0.3664475623693453 + 51.5150045658266 + 14.61465933947184 + 0 + 0 + 35 + 5170.4788906232 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.3659851248043444,51.50986627410659,29.45152708742405 + + + + King George Hospital + + 0.1131400861304566 + 51.6036926176623 + 34.77471337249119 + 0 + 0 + 35 + 20172.14336291654 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1115406191337875,51.58020252921018,28.66285418751985 + + + + Amersham Hospital + + -0.6342053682990934 + 51.66509123897674 + 149.5720681058467 + 0 + 0 + 35 + 13772.91424037889 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.6219161072258006,51.66248155450033,104.6373374748187 + + + + Wexham Park Hospital + + -0.5762301074521392 + 51.53097676898582 + 39.26576307603242 + 0 + 0 + 35 + 10412.39299668116 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.5743065471308129,51.53198531659324,40.26845657665874 + + + + Hillingdon Hospital + + -0.4679403951494432 + 51.52584487861473 + 27.21307323300876 + 0 + 0 + 35 + 5016.97494800901 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.461237980769241,51.52520706750175,42.05823445105383 + + + + Chepstow Garden Medical Centre + + -0.3743511306119784 + 51.51983377508201 + 35.59607571201144 + 0 + 0 + 35 + 2047.961368760734 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3751830368179809,51.51764542612705,36.24763743995023 + + + + Jubilee Garden Medical Centre + + -0.3743511306119784 + 51.51983377508201 + 35.59607571201144 + 0 + 0 + 35 + 2047.961368760734 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3692423185887139,51.52124238610774,45.62938978512876 + + + + Shackleton Care + + -0.3762781686906969 + 51.51334896492931 + 26.6306137555698 + 0 + 0 + 35 + 613.3674930026609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.376576046380791,51.51400575461064,33.02093250534271 + + + + Lady Margaret Road Medical Centre + + -0.3762781686906969 + 51.51334896492931 + 26.6306137555698 + 0 + 0 + 35 + 613.3674930026609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3756876450724222,51.51322413221729,31.79962578264546 + + + + Ealing Hospital + + -0.3475974152001449 + 51.50816120422 + 26.53977458429974 + 0 + 0 + 35 + 1159.575944942044 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3465248149688316,51.50751868302849,10.97122643493213 + + + + Northwick Park Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3202882107130534,51.57532030752736,59.37782426476122 + + + + The Clementine Churchil Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3321707589285809,51.5650667535168,85.33377956359243 + + + + Edgware Community Hospital + + -0.2973051811121885 + 51.57906350022693 + 47.02083249058781 + 0 + 0 + 35 + 23026.81813610718 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2710066678387879,51.60647115563065,47.77192794539427 + + + + North Middlesex University Hospital + + -0.09826342248914433 + 51.59887136142904 + 16.29834450224789 + 0 + 0 + 35 + 17954.37715320149 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.07348212287029532,51.61310744874702,16.34704237642337 + + + + Whipps Cross University Hospital + + -0.00318 + 51.57791 + 21.12856769576882 + 0 + 0 + 35 + 23339.02225369122 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + -0.03464309208118022,51.84623406486086,26.76480826700025 + + + + Chase Farm Hospital + + -0.09445976388827715 + 51.64827324649203 + 45.18742363056923 + 0 + 0 + 35 + 20112.77904122835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1028073489011011,51.66689124911596,65.56377192754866 + + + + The Cavell Hospital + + -0.09445976388827715 + 51.64827324649203 + 45.18742363056923 + 0 + 0 + 35 + 20112.77904122835 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1004158897945784,51.65899468845168,65.56296912431105 + + +
+ + Vale Drive Primary Care Centre + + -0.1968710123449446 + 51.65064622007617 + 119.0496245502007 + 33.95610494125125 + 51.61511454086038 + 35 + 783.3107969355478 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1951169862852115,51.6497469421364,106.8249971668427 + + + + Broomfield Hospital + + 0.4658531148979139 + 51.7730741281356 + 53.91494881236988 + -2.457264969088007 + 0.8143978401954622 + 35 + 962.681589408021 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4661826118043533,51.77432116677244,62.15314977461038 + + + + Colchester Hospital + + 0.8977119812889867 + 51.897302757459 + 9.164679933150786 + 8.311353741625599e-08 + 5.69202850576525 + 35 + 7908.249561059058 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.8989016354739056,51.90985612864645,52.129981717103 + + + + Oaks Hospital + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + 0.8950007512019129,51.90631333268821,40.85532839312136 + + + + Primary Care Centre + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.9020700978708827,51.90668078352024,41.05316266193498 + + + + Springfield Hospital + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4847439958367916,51.75341033368938,37.20936407432514 + + + + Chelmsford Ambulance Station + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.486090691535023,51.75595480607432,30.37470452823173 + + + + Chelmsford Medical Partnership + + 0.490010317636238 + 51.74347030470852 + 41.0383120629581 + 8.400205233656506e-08 + 5.686681664178874 + 35 + 1906.346236672543 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4851154704670301,51.74716663521045,42.72730373314561 + + + + St Margaret's Hospital + + 0.1249376747268771 + 51.7056521315599 + 114.9181035087347 + 8.43019173841836e-08 + 5.69293409158565 + 35 + 8924.934771554545 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1237980769230785,51.70491929118251,115.6421697734014 + + + + Princess Alexander Hospital + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.08539556146978197,51.76952006829818,64.14747173662603 + + + + Princess Alexandra Hospital Emergency Dep + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.0868200246143358,51.77176739550571,69.79413382101708 + + + + The Hamilton Practice + + 0.09407606608095032 + 51.76102983091437 + 62.82177510919995 + 8.385446841027487e-08 + 5.687801445829821 + 35 + 3163.337353592506 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1129865782056449,51.75607366423915,73.36016156645285 + + + + Rivers Hospital + + 0.1269921237352722 + 51.80593562347006 + 76.90405189061812 + 8.35673695662816e-08 + 5.690141647479414 + 35 + 5790.285723345587 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.1356597399818305,51.80818175439256,68.28605103152285 + + + + Southend University Hospital + + 0.686807362759585 + 51.55442186733111 + 38.34213267175858 + 53.39226911898427 + 59.94270415751299 + 35 + 180.7781594831977 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.6877328222924616,51.55385927682786,40.11469741632487 + + + + St Albans City Hospital + + -0.3457139310618307 + 51.74319846245394 + 91.24766614316273 + 53.11981616282007 + 60.0613137551813 + 35 + 15419.13049176335 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.3435461023351755,51.76043771309943,110.8324392548333 + + + + Hemel Hempsteam Hospital + + -0.4695075770543722 + 51.75069927539609 + 108.933477195889 + 52.91641952113871 + 59.94724979383651 + 35 + 764.7829484937392 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.4691092344696746,51.7516592203038,124.3043795309861 + + + + Stoke Mandeville Hospital + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8061987654715064,51.81044035125617,88.5627270743543 + + + + Stoke Mandeville Hospital Emergency + + -0.7978240106556145 + 51.79912316487393 + 86.01612159447117 + 52.82577528013368 + 51.35198755734502 + 35 + 1424.284711338842 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8014090401785613,51.79736510287374,90.28124226004431 + + + + Waddesdon Wing Maternity Outpatients Antenatal + + -0.8021384379958951 + 51.79719545416784 + 90.92761652804441 + 52.81887036614162 + 51.34717542765949 + 35 + 739.049740673363 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.8000927812905456,51.79724865426316,92.9616022829897 + + + + Phoenix Hospital Chelmsford + + 0.4693273523125319 + 51.71077841110404 + 67.2959564377251 + 34.37350968852617 + 51.66017289287989 + 35 + 7175.670542574953 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.5035843063186717,51.70695925794588,36.53239001018486 + + + + Chelmsford & Essex Hospita + + 0.4723566742305252 + 51.73189932639333 + 23.32981638330202 + 34.3362298903192 + 51.61801892945288 + 35 + 1195.337775519001 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4710096422132502,51.73092405457083,35.83657572852461 + + + + Stapleford House + + 0.4683472433281599 + 51.72932847109089 + 35.19844820185988 + 34.33482353995927 + 51.61768196773221 + 35 + 1147.535923757823 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.4663354223901122,51.72999144599144,31.24564959711314 + + + + Whitley House Surgery + + 0.4574225151539602 + 51.72370337607269 + 53.76763205449836 + 34.32854201256372 + 51.62043206484431 + 35 + 1537.691036219039 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.456043285327947,51.72642076891589,48.45157475308184 + + + + The Writtle Surgery + + 0.4307278930562286 + 51.72920902048297 + 41.74006982584603 + 34.31337571691095 + 51.62858416804543 + 35 + 2694.211246461491 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + 0.42651098901098,51.73261225563316,35.54494197837538 + + + + Barnet Hospital + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.213735727163469,51.6508233199992,115.5282869113015 + + + + Barnet Hospital Emergency Department + + -0.2142299080354926 + 51.65015280865894 + 116.3103679142327 + 33.94792626631624 + 51.61979249013329 + 35 + 1446.969833067415 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.2161576826493854,51.65055615262246,125.5996772205984 + + + + Hadley Wood Hospital + + -0.1981320364942063 + 51.65279534597052 + 125.0634923173999 + 33.95924878558147 + 51.61956884043195 + 35 + 1415.242666276609 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1969832535628527,51.65449483924015,112.7852073322038 + + + + Medstar Clinic + + -0.1504930494292478 + 51.61739661253369 + 52.08032173071229 + 33.97802065777326 + 51.61813033259048 + 35 + 1211.147772304685 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.1514262105082491,51.61601546985334,60.94665359539616 + + + + Lordship Lane Primary Care Centre + + -0.08535541171442618 + 51.59570416495118 + 14.86720000060767 + 34.00430616452158 + 51.62460473348132 + 35 + 2129.647572840331 + absolute + + #__managed_style_028CF56A8C31BD208B69 + + -0.0805596990899683,51.5972710103994,21.36209261262719 + + + + Cheshunt Community Hospital + + -0.03335 + 51.6996 + 28.21933806852695 + 34.05244126896145 + 51.63689768466914 + 35 + 3873.625454957946 + absolute + + #__managed_style_0CC5D867B031BD754BC2 + + -0.03848996120356829,1,25.78451729971917 + + +
+
+
diff --git a/PathPlanning/DynamicWindowApproach/mavproxy_kml.py b/PathPlanning/DynamicWindowApproach/mavproxy_kml.py new file mode 100644 index 0000000000..04da8d997c --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/mavproxy_kml.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import pexpect +import time + +# Define the MAVProxy command +mavproxy_cmd1 = "mavproxy.py --master=udpin:127.0.0.1:14550 --console --map --out=udpout:127.0.0.1:14552" +mavproxy_cmd2 = "mavproxy.py --master=udpin:127.0.0.1:14551 --console --map --out=udpout:127.0.0.1:14553" +# Start MAVProxy +child = pexpect.spawn(mavproxy_cmd1) +child = pexpect.spawn(mavproxy_cmd2) +# Wait for MAVProxy to load +child.expect("Received", timeout=60) + +# Load the kmlread module +child.sendline("module load kmlread") + +# Wait for the module to load +time.sleep(2) + +# Load the KML file +child.sendline("kml load /home/dell/Essex_Hospitals_NoFlyZones.kml") + +# Give some time for the KML to load and process +time.sleep(5) + +# Optionally, you can add more commands here, e.g., to toggle visibility or create fences + +# Interact with MAVProxy console +child.interact() + From 235933f67d87e3b6fc9a8c5b8600e6ff89e3da24 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:17:09 +0100 Subject: [PATCH 25/33] Add files via upload --- .../DynamicWindowApproach/Destinations.kml | 620 +++++++++ .../DynamicWindowApproach/Destinations.tsp | 34 + PathPlanning/DynamicWindowApproach/Fences.kml | 1165 ++++++++++++++++ PathPlanning/DynamicWindowApproach/Fences.tsp | 1206 +++++++++++++++++ .../convert_KML_to_TSP.py | 38 + 5 files changed, 3063 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/Destinations.kml create mode 100644 PathPlanning/DynamicWindowApproach/Destinations.tsp create mode 100644 PathPlanning/DynamicWindowApproach/Fences.kml create mode 100644 PathPlanning/DynamicWindowApproach/Fences.tsp create mode 100644 PathPlanning/DynamicWindowApproach/convert_KML_to_TSP.py diff --git a/PathPlanning/DynamicWindowApproach/Destinations.kml b/PathPlanning/DynamicWindowApproach/Destinations.kml new file mode 100644 index 0000000000..0ace74f94d --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Destinations.kml @@ -0,0 +1,620 @@ + + + + NATS AIM on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.
+ The content of this file is not guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free.]]>
+ + 2024-06-13 + 2024-06-13 + + + + + + + + + + normal + #__managed_style_1DCA19CD8A31C486AD3A + + + highlight + #__managed_style_274497110631C486AD3A + + + + + + + + + + + normal + #__managed_style_1BA48B6AA031C486AD38 + + + highlight + #__managed_style_21EFB6D05B31C486AD38 + + + + Destinations + + Broomfield Hospital + + 0.4658531148979139 + 51.7730741281356 + 53.91494881236988 + -2.457264969088007 + 0.8143978401954622 + 35 + 962.681589408021 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4661826118043533,51.77432116677244,62.15314977461038 + + + + Colchester Hospital + + 0.8977119812889867 + 51.897302757459 + 9.164679933150786 + 8.311353741625599e-08 + 5.69202850576525 + 35 + 7908.249561059058 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.8989016354739056,51.90985612864645,52.129981717103 + + + + Oaks Hospital + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.8950007512019129,51.90631333268821,40.85532839312136 + + + + Primary Care Centre + + 0.8962564781296689 + 51.90083156103237 + 14.15699535515697 + 8.35400606203151e-08 + 5.688603182799385 + 35 + 4063.273102276144 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.9020700978708827,51.90668078352024,41.05316266193498 + + + + Springfield Hospital + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4847439958367916,51.75341033368938,37.20936407432514 + + + + Chelmsford Ambulance Station + + 0.4895936338277007 + 51.75553800581241 + 41.39576614457171 + 8.397329951501253e-08 + 5.688113084849667 + 35 + 3513.147033427376 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4860906915350229,51.75595480607432,30.37470452823173 + + + + Chelmsford Medical Partnership + + 0.490010317636238 + 51.74347030470852 + 41.0383120629581 + 8.400205233656506e-08 + 5.686681664178874 + 35 + 1906.346236672543 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4851154704670301,51.74716663521045,42.72730373314561 + + + + St Margaret's Hospital + + 0.1249376747268771 + 51.7056521315599 + 114.9181035087347 + 8.43019173841836e-08 + 5.69293409158565 + 35 + 8924.934771554545 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.1255747078023273,51.70288283015128,115.6421697734014 + + + + Princess Alexander Hospital + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.08565868894554463,51.76912716012718,64.14747173662603 + + + + Princess Alexandra Hospital Emergency Dep + + 0.08388849248676777 + 51.76516670815253 + 64.57774466587422 + 8.399056076465016e-08 + 5.687537581102137 + 35 + 2867.143209121423 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.08681342944926174,51.77177470864583,69.79413382101708 + + + + The Hamilton Practice + + 0.09407606608095032 + 51.76102983091437 + 62.82177510919995 + 8.385446841027487e-08 + 5.687801445829821 + 35 + 3163.337353592506 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.1129865782056449,51.75607366423915,73.36016156645285 + + + + Rivers Hospital + + 0.1269921237352722 + 51.80593562347006 + 76.90405189061812 + 8.35673695662816e-08 + 5.690141647479414 + 35 + 5790.285723345587 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.1357804869768531,51.80828291123409,68.28605103152285 + + + + Southend University Hospital + + 0.686807362759585 + 51.55442186733111 + 38.34213267175858 + 53.39226911898427 + 59.94270415751299 + 35 + 180.7781594831977 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.6877328222924616,51.55385927682786,40.11469741632487 + + + + Phoenix Hospital Chelmsford + + 0.4693273523125319 + 51.71077841110404 + 67.2959564377251 + 34.37350968852617 + 51.66017289287989 + 35 + 7175.670542574953 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.5035843063186717,51.70695925794588,36.53239001018486 + + + + Chelmsford & Essex Hospita + + 0.4723566742305252 + 51.73189932639333 + 23.32981638330202 + 34.3362298903192 + 51.61801892945288 + 35 + 1195.337775519001 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4710096422132502,51.73092405457083,35.83657572852461 + + + + Stapleford House + + 0.4683472433281599 + 51.72932847109089 + 35.19844820185988 + 34.33482353995927 + 51.61768196773221 + 35 + 1147.535923757823 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4663354223901122,51.72999144599143,31.24564959711314 + + + + Whitley House Surgery + + 0.4574225151539602 + 51.72370337607269 + 53.76763205449836 + 34.32854201256372 + 51.62043206484431 + 35 + 1537.691036219039 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.456043285327947,51.72642076891589,48.45157475308184 + + + + The Writtle Surgery + + 0.4307278930562286 + 51.72920902048297 + 41.74006982584603 + 34.31337571691095 + 51.62858416804543 + 35 + 2694.211246461491 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.42651098901098,51.73261225563316,35.54494197837538 + + + + Cheshunt Community Hospital + + -0.03335 + 51.6996 + 28.21933806852695 + 34.05244126896145 + 51.63689768466914 + 35 + 3873.625454957946 + absolute + + #__managed_style_0104C73C4731C486AD3A + + -0.03848996120356829,1,25.78451729971917 + + + + Fitzory Surgery Chelmsford + + 0.474960331146792 + 51.73517761738581 + 40.78990233500093 + 0 + 0 + 35 + 829.7059538363828 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.473230589786886,51.73593592005771,38.36438983225385 + + + + Brentwood Community Hospital + + 0.3171528392735157 + 51.62609308593774 + 99.40971056935952 + 0 + 0 + 35 + 9806.023979805177 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.3165310777240293,51.62350362985205,109.6301263398982 + + + + Mayflower Community Hospital + + 0.4023120334724561 + 51.62731403373353 + 60.22327431393138 + 0 + 0 + 35 + 5621.724128820934 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4050319797390081,51.62170280073786,74.70768879269713 + + + + West Horndon Surgery + + 0.3560545232035661 + 51.56780143023479 + 11.8024814363113 + 0 + 0 + 35 + 4198.395910652471 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.3478919772586697,51.56991740445563,11.81273275657717 + + + + Orsett Hospital + + 0.3246751037585205 + 51.55178329697734 + 4.008712259332912 + 0 + 0 + 35 + 23217.31797739863 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.3662846514279683,51.50992194663591,28.58734636932077 + + + + Basildon University Hospital + + 0.4683344842514447 + 51.55814670533533 + 62.20367310984593 + 0 + 0 + 35 + 5148.914823020459 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.4518533224587952,51.55800000431004,57.89818970777221 + + + + Sutherland Lodge Surgery + + 0.4790806956315974 + 51.73013599557864 + 22.04054520405848 + 0 + 0 + 35 + 2563.299715178437 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.482412970012287,51.7257098800565,30.20589758874257 + + + + Braintree Community Hospital + + 0.5484712809762371 + 51.87140860174407 + 45.57400011538562 + 0 + 0 + 35 + 5378.982349414146 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.5404728217711163,51.87983379657575,73.71777320795582 + + + + Halstead Hospital + + 0.6308253311851253 + 51.94110862866791 + 55.87094588961648 + 0 + 0 + 35 + 4196.559132258408 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.6379421359890148,51.94822718909321,56.15721830449306 + + + + Colchester General Hospital + + 0.8999150581272652 + 51.91029998454125 + 43.54285943894751 + 0 + 0 + 35 + 614.4730181369232 + absolute + + #__managed_style_00BA56A43631C486AD38 + + 0.8993085991404359,51.91038853812569,52.05996642334027 + + + +
+
diff --git a/PathPlanning/DynamicWindowApproach/Destinations.tsp b/PathPlanning/DynamicWindowApproach/Destinations.tsp new file mode 100644 index 0000000000..15cf1cc301 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Destinations.tsp @@ -0,0 +1,34 @@ +NAME: example +TYPE: TSP +DIMENSION: 29 +EDGE_WEIGHT_TYPE: EUC_2D +NODE_COORD_SECTION +1 51.77432116677244 0.4661826118043533 +2 51.90985612864645 0.8989016354739056 +3 51.90631333268821 0.8950007512019129 +4 51.90668078352024 0.9020700978708827 +5 51.75341033368938 0.4847439958367916 +6 51.75595480607432 0.4860906915350229 +7 51.74716663521045 0.4851154704670301 +8 51.70288283015128 0.1255747078023273 +9 51.76912716012718 0.08565868894554463 +10 51.77177470864583 0.08681342944926174 +11 51.75607366423915 0.1129865782056449 +12 51.80828291123409 0.1357804869768531 +13 51.55385927682786 0.6877328222924616 +14 51.70695925794588 0.5035843063186717 +15 51.73092405457083 0.4710096422132502 +16 51.72999144599143 0.4663354223901122 +17 51.72642076891589 0.456043285327947 +18 51.73261225563316 0.42651098901098 +19 51.73593592005771 0.473230589786886 +20 51.62350362985205 0.3165310777240293 +21 51.62170280073786 0.4050319797390081 +22 51.56991740445563 0.3478919772586697 +23 51.50992194663591 0.3662846514279683 +24 51.55800000431004 0.4518533224587952 +25 51.7257098800565 0.482412970012287 +26 51.87983379657575 0.5404728217711163 +27 51.94822718909321 0.6379421359890148 +28 51.91038853812569 0.8993085991404359 +EOF diff --git a/PathPlanning/DynamicWindowApproach/Fences.kml b/PathPlanning/DynamicWindowApproach/Fences.kml new file mode 100644 index 0000000000..4c98eed1ce --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Fences.kml @@ -0,0 +1,1165 @@ + + + + NATS AIM on 2024-04-16 11:38:58 using data effective 2024-06-13. Not for operational use.
+ The content of this file is not guaranteed as accurate, adequate, fit for any particular purpose, complete, reliable, current, or error-free.]]>
+ + 2024-06-13 + 2024-06-13 + + + + + + normal + #rdpstyle + + + highlight + #highlightStyle + + + + Airspaces + 1 + + Danger + 1 + + EGD136 SHOEBURYNESS + 513217N 0004804E -
513017N 0005104E -
513030N 0004700E -
513217N 0004804E
Upper limit: 13000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8011111111,51.5380555556,3962.4 0.7833333333,51.5083333333,3962.4 0.8511111111000002,51.50472222219999,3962.4 0.8011111111,51.5380555556,3962.4 + + + + +
+ + EGD138A SHOEBURYNESS + 514000N 0010400E -
514000N 0011613E -
513714N 0011203E -
513714N 0005536E -
514000N 0010400E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 6000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0666666667,51.6666666667,18288 0.9266666667,51.6205555556,18288 1.2008333333,51.6205555556,18288 1.2702777778,51.6666666667,18288 1.0666666667,51.6666666667,18288 + + + + +
+ + EGD138B SHOEBURYNESS + 514200N 0011124E -
514200N 0011912E -
514000N 0011613E -
514000N 0010400E -
514200N 0011124E
Upper limit: 5000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.19,51.7,1524 1.0666666667,51.6666666667,1524 1.2702777778,51.6666666667,1524 1.32,51.7,1524 1.19,51.7,1524 + + + + +
+ + EGD138C SHOEBURYNESS + 513700N 0005455E -
513755N 0005740E -
513638N 0005850E -
513544N 0005620E -
513700N 0005455E
Upper limit: 6000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: May be activated at the same time as EGD138A and/or EGD138D as a separate activity.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9152777778000001,51.6166666667,1828.8 0.9388888889,51.5955555556,1828.8 0.9805555555999999,51.6105555556,1828.8 0.9611111111,51.63194444440001,1828.8 0.9152777778000001,51.6166666667,1828.8 + + + + +
+ + EGD138D SHOEBURYNESS + 513714N 0005536E -
513714N 0011203E -
513000N 0005300E -
513009N 0005115E -
513217N 0004804E -
513400N 0005000E -
513500N 0005018E -
513541N 0005016E - then along the north coast of Foulness Island to
513700N 0005455E -
513714N 0005536E
Upper limit: 60000 FT MSL
Lower limit: SFC
Class: AMC - Manageable.

Vertical Limits: 13,000 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 60,000 FT ALT.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS/BVLOS) / Electronic/Optical Hazards.

Service: SUAAIS: Southend APP on 130.780 MHz when open; at other times London Information on 124.600 MHz.

Contact: Pre-flight information: Range Control, Tel: 01702-383211 or 01702-383212.

Remarks: SI 1936/714.

Danger Area Authority: DE&S.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9266666667,51.6205555556,18288 0.9152777778000001,51.6166666667,18288 0.915875,51.61495,18288 0.913075,51.6141194444,18288 0.9085638888999999,51.61360000000001,18288 0.9064277777999999,51.61410277779999,18288 0.9046694444,51.6136972222,18288 0.9015722222,51.6126944444,18288 0.8996138888999999,51.61373333329999,18288 0.8951472221999999,51.6139333333,18288 0.8891527778,51.6150694444,18288 0.877525,51.6140055556,18288 0.8742555556,51.61255833330001,18288 0.87235,51.6098166667,18288 0.8720472222,51.6004694444,18288 0.87065,51.5966361111,18288 0.8677638889000001,51.5943666667,18288 0.8625527777999999,51.5918861111,18288 0.8590694444,51.5916111111,18288 0.8508555556,51.5919,18288 0.8451333333,51.5927583333,18288 0.8405138889,51.59278055560001,18288 0.8377777778000001,51.5947222222,18288 0.8383333333,51.58333333329999,18288 0.8333333333000001,51.5666666667,18288 0.8011111111,51.5380555556,18288 0.8541666667,51.50249999999999,18288 0.8833333333,51.5,18288 1.2008333333,51.6205555556,18288 0.9266666667,51.6205555556,18288 + + + + +
+ + EGD139 FINGRINGHOE + 515000N 0005458E -
514954N 0005852E -
514833N 0005848E -
514839N 0005452E -
515000N 0005458E
Upper limit: 2000 FT MSL
Lower limit: SFC
Class: Vertical Limits: 1500 FT ALT.

Vertical Limits: OCNL notified to altitudes up to 2000 FT ALT by NOTAM.

Activity: Ordnance, Munitions and Explosives / Unmanned Aircraft System (VLOS).

Service: SUAAIS: London Information on 124.600 MHz.

Contact: Pre-flight information / Booking: Range TSO, Tel: 01206-736149.

Remarks: SI 1974/665.

Danger Area Authority: DIO.]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9161111111,51.83333333329999,609.6 0.9144444443999998,51.8108333333,609.6 0.98,51.8091666667,609.6 0.9811111111000002,51.8316666667,609.6 0.9161111111,51.83333333329999,609.6 + + + + +
+
+ + Restricted + 1 + + EGR157 HYDE PARK + 513212N 0000911W -
513020N 0000648W thence clockwise by the arc of a circle radius 0.55 NM centred on 513000N 0000730W to
513001N 0000637W -
512917N 0000634W thence clockwise by the arc of a circle radius 0.55 NM centred on 512915N 0000726W to
512852N 0000649W -
512834N 0000719W thence clockwise by the arc of a circle radius 0.55 NM centred on 512857N 0000756W to
512858N 0000849W -
512921N 0000847W -
512939N 0001132W thence clockwise by the arc of a circle radius 0.55 NM centred on 513011N 0001123W to
513028N 0001209W -
513208N 0001038W thence clockwise by the arc of a circle radius 0.55 NM centred on 513151N 0000952W to -
513212N 0000911W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 1300/2017

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1529333333,51.53661111109999,426.7200000000001 -0.1549267573,51.53789408709999,426.7200000000001 -0.1572818369,51.5389111961,426.7200000000001 -0.1599088899,51.5396236997,426.7200000000001 -0.1627078613,51.5400044583,426.7200000000001 -0.1655721364,51.5400389683,426.7200000000001 -0.1683926087,51.5397259152,426.7200000000001 -0.1710618431,51.5390772237,426.7200000000001 -0.1734781752,51.53811760280001,426.7200000000001 -0.1755495885,51.5368836029,426.7200000000001 -0.1771972222,51.5354222222,426.7200000000001 -0.2023722222,51.5076638889,426.7200000000001 -0.2035115549,51.5060699613,426.7200000000001 -0.2041447262,51.5043699176,426.7200000000001 -0.2042494731,51.5026257804,426.7200000000001 -0.2038220493,51.5009009245,426.7200000000001 -0.2028780428,51.4992580171,426.7200000000001 -0.2014518003,51.4977567415,426.7200000000001 -0.1995951734,51.4964516304,426.7200000000001 -0.1973756297,51.4953900866,426.7200000000001 -0.1948738011,51.4946106635,426.7200000000001 -0.1921805556,51.4941416667,426.7200000000001 -0.1464694444,51.4890388889,426.7200000000001 -0.1468722222,51.48287500000001,426.7200000000001 -0.1467340709,51.4811955082,426.7200000000001 -0.1461068208,51.4795600798,426.7200000000001 -0.1450111174,51.4780238809,426.7200000000001 -0.1434839716,51.4766387391,426.7200000000001 -0.141576937,51.4754513811,426.7200000000001 -0.1393543671,51.47450185809999,426.7200000000001 -0.1368912443,51.47382219699999,426.7200000000001 -0.1342706517,51.4734353207,426.7200000000001 -0.1315809745,51.4733542773,426.7200000000001 -0.1289129236,51.4735818,426.7200000000001 -0.1263564821,51.4741102153,426.7200000000001 -0.1239978753,51.4749217016,426.7200000000001 -0.1219166667,51.4759888889,426.7200000000001 -0.1136111111,51.48111111110001,426.7200000000001 -0.1120090522,51.482252708,426.7200000000001 -0.1107683543,51.483560414,426.7200000000001 -0.109891236,51.4849782611,426.7200000000001 -0.1094019057,51.4864671731,426.7200000000001 -0.1093138889,51.4879861111,426.7200000000001 -0.1102416667,51.5003194444,426.7200000000001 -0.1105268172,51.5017362939,426.7200000000001 -0.1111609871,51.50310830229999,426.7200000000001 -0.1121293381,51.50440206899999,426.7200000000001 -0.1134083333,51.5055861111,426.7200000000001 -0.1529333333,51.53661111109999,426.7200000000001 + + + + +
+ + EGR158 CITY OF LONDON + 513125N 0000547W -
513118N 0000439W -
513043N 0000418W -
513016N 0000433W -
513037N 0000704W -
513108N 0000653W -
513125N 0000547W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit.

See also ENR 1.1, paragraph 4.1.6.

SI 2092/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.09652500000000001,51.52371388890001,426.7200000000001 -0.1147444444,51.5188833333,426.7200000000001 -0.1176944444,51.5102972222,426.7200000000001 -0.0757138889,51.5044888889,426.7200000000001 -0.0716472222,51.51206666669999,426.7200000000001 -0.07758611109999999,51.5216055556,426.7200000000001 -0.09652500000000001,51.52371388890001,426.7200000000001 + + + + +
+ + EGR159 ISLE OF DOGS + 513035N 0000025W -
512954N 0000033W -
512938N 0000022W thence clockwise by the arc of a circle radius 0.3 NM centred on 512931N 0000049W to
512921N 0000113W -
513000N 0000154W thence clockwise by the arc of a circle radius 0.55 NM centred on 513018N 0000110W to -
513035N 0000025W
Upper limit: 1400 FT MSL
Lower limit: SFC
Class: Flight permitted by:
any aircraft in the service of the Chief Officer of Police for the Metropolitan Police District;
any aircraft flying in accordance with a Special Flight Notification issued by the appropriate ATC unit;
any helicopter flying on Helicopter Route H4;
any aircraft flying in accordance with an Enhanced Non-Standard Flight clearance issued by the appropriate ATC unit;
any aircraft approaching to, or departing from, London/City Airport.

See also ENR 1.1, paragraph 4.1.6.

SI 2091/2004.

Contact: www.nats.co.uk/nsf]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0068583333,51.5097055556,426.7200000000001 -0.0082867913,51.5111814939,426.7200000000001 -0.0103077723,51.5123684169,426.7200000000001 -0.0126486151,51.51329883229999,426.7200000000001 -0.0152268831,51.5139399674,426.7200000000001 -0.0179517632,51.51426923799999,426.7200000000001 -0.020727269,51.51427504499999,426.7200000000001 -0.0234556276,51.5139571838,426.7200000000001 -0.0260407298,51.5133268516,426.7200000000001 -0.0283915214,51.51240625220001,426.7200000000001 -0.030425215,51.5112278124,426.7200000000001 -0.0320702078,51.5098330386,426.7200000000001 -0.0332686036,51.50827105250001,426.7200000000001 -0.0339782479,51.5065968595,426.7200000000001 -0.0341742076,51.5048694103,426.7200000000001 -0.0338496416,51.5031495242,426.7200000000001 -0.033016033,51.5014977474,426.7200000000001 -0.0317027778,51.4999722222,426.7200000000001 -0.0202666667,51.48911111110001,426.7200000000001 -0.0187899397,51.4881604117,426.7200000000001 -0.0170196811,51.4874451822,426.7200000000001 -0.0150110296,51.4870446916,426.7200000000001 -0.0129044713,51.4869869497,426.7200000000001 -0.0108473335,51.4872759947,426.7200000000001 -0.008983490199999999,51.4878916114,426.7200000000001 -0.0074433086,51.4887907435,426.7200000000001 -0.0063345359,51.4899105027,426.7200000000001 -0.005734762,51.4911725642,426.7200000000001 -0.005685986,51.49248864270001,426.7200000000001 -0.0061916667,51.4937666667,426.7200000000001 -0.009272222199999999,51.49840277780001,426.7200000000001 -0.0068583333,51.5097055556,426.7200000000001 + + + + +
+ + EGRU126C FAIROAKS RWY 24 + 512239N 0002949W -
512212N 0002922W -
512142N 0003037W thence anti-clockwise by the arc of a circle radius 2 NM centred on 512053N 0003331W to
512210N 0003104W -
512239N 0002949W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4969416667,51.37758888890001,609.6 -0.5178943056,51.3693692222,609.6 -0.5149878589,51.3669779903,609.6 -0.5124379479,51.3644324142,609.6 -0.5102653056000001,51.36175325,609.6 -0.4893055556,51.369975,609.6 -0.4969416667,51.37758888890001,609.6 + + + + +
+ + EGRU127A DENHAM + A circle, 2 NM radius, centred at 513518N 0003047W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5129944444,51.6217164382,609.6 -0.5184936191,51.62153986119999,609.6 -0.5239343742,51.621012006,609.6 -0.5292589149,51.6201384801,609.6 -0.5344106889,51.6189285623,609.6 -0.5393349903,51.6173951042,609.6 -0.5439795438,51.6155543924,609.6 -0.5482950621,51.6134259744,609.6 -0.5522357706,51.6110324506,609.6 -0.5557598936,51.608399232,609.6 -0.5588300976,51.60555427029999,609.6 -0.5614138859,51.60252775930001,609.6 -0.5634839411,51.5993518132,609.6 -0.5650184115,51.59606012529999,609.6 -0.5660011389,51.5926876095,609.6 -0.5664218254,51.589270029,609.6 -0.5662761375000001,51.585843617,609.6 -0.5655657464,51.5824446922,609.6 -0.5642983056999999,51.57910927410001,609.6 -0.5624873639,51.57587270119999,609.6 -0.5601522173,51.5727692576,609.6 -0.5573177001,51.5698318103,609.6 -0.5540139185,51.5670914623,609.6 -0.5502759287,51.56457722420001,609.6 -0.5461433639,51.56231570839999,609.6 -0.5416600139,51.56033084849999,609.6 -0.5368733613,51.55864364759999,609.6 -0.5318340803,51.5572719567,609.6 -0.5265955023,51.5562302872,609.6 -0.5212130538999999,51.5555296584,609.6 -0.5157436739,51.5551774815,609.6 -0.510245215,51.5551774815,609.6 -0.504775835,51.5555296584,609.6 -0.4993933866,51.5562302872,609.6 -0.4941548086,51.5572719567,609.6 -0.4891155276,51.55864364759999,609.6 -0.484328875,51.56033084849999,609.6 -0.4798455249,51.56231570839999,609.6 -0.4757129602,51.56457722420001,609.6 -0.4719749703,51.5670914623,609.6 -0.4686711888000001,51.5698318103,609.6 -0.4658366715999999,51.5727692576,609.6 -0.4635015249,51.57587270119999,609.6 -0.4616905832,51.57910927410001,609.6 -0.4604231424,51.5824446922,609.6 -0.4597127514,51.585843617,609.6 -0.4595670635,51.589270029,609.6 -0.4599877499,51.5926876095,609.6 -0.4609704774,51.59606012529999,609.6 -0.4625049477,51.5993518132,609.6 -0.464575003,51.60252775930001,609.6 -0.4671587913,51.60555427029999,609.6 -0.4702289953,51.608399232,609.6 -0.4737531183000001,51.6110324506,609.6 -0.4776938267,51.6134259744,609.6 -0.4820093451,51.6155543924,609.6 -0.4866538986,51.6173951042,609.6 -0.4915782,51.6189285623,609.6 -0.4967299739,51.6201384801,609.6 -0.5020545147,51.621012006,609.6 -0.5074952698,51.62153986119999,609.6 -0.5129944444,51.6217164382,609.6 + + + + +
+ + EGRU127B DENHAM RWY 06 + 513336N 0003432W -
513404N 0003459W -
513431N 0003344W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513404N 0003317W -
513336N 0003432W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5756055556,51.5599277778,609.6 -0.5547771667,51.56767425,609.6 -0.5576101111,51.57010516770001,609.6 -0.5600801312,51.5726852958,609.6 -0.5621670833,51.5753936389,609.6 -0.5829861111,51.56765,609.6 -0.5756055556,51.5599277778,609.6 + + + + +
+ + EGRU127C DENHAM RWY 24 + 513700N 0002704W -
513632N 0002637W -
513605N 0002750W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513633N 0002816W -
513700N 0002704W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.450975,51.6166444444,609.6 -0.4711767778000001,51.60916325,609.6 -0.4683454518999999,51.6067302115,609.6 -0.4658782366,51.6041480831,609.6 -0.4637951944,51.6014379167,609.6 -0.4435833333,51.6089222222,609.6 -0.450975,51.6166444444,609.6 + + + + +
+ + EGRU127D DENHAM RWY 12 + 513623N 0003455W -
513652N 0003431W -
513629N 0003322W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513600N 0003347W -
513623N 0003455W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5820527778,51.6064472222,609.6 -0.5630313056,51.6001324167,609.6 -0.5611342148,51.6028946338,609.6 -0.5588447291,51.6055390603,609.6 -0.5561814443999999,51.6080441389,609.6 -0.57525,51.61437500000001,609.6 -0.5820527778,51.6064472222,609.6 + + + + +
+ + EGRU127E DENHAM RWY 30 + 513416N 0002641W -
513347N 0002706W -
513409N 0002810W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513518N 0003047W to
513437N 0002746W -
513416N 0002641W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4448222222000001,51.57097499999999,609.6 -0.4628163333,51.57697613890001,609.6 -0.464678404,51.5742051095,609.6 -0.4669335187,51.5715499091,609.6 -0.4695632778,51.5690321389,609.6 -0.4516166667,51.5630472222,609.6 -0.4448222222000001,51.57097499999999,609.6 + + + + +
+ + EGRU128A LONDON HEATHROW + A circle, 2.5 NM radius, centred at 512839N 0002741W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.46135,51.519198392,609.6 -0.4675046258,51.5190207088,609.6 -0.4736065998,51.5184891791,609.6 -0.4796037246,51.51760834980001,609.6 -0.4854447065999999,51.5163857558,609.6 -0.4910795983,51.5148318544,609.6 -0.4964602286,51.51295993590001,609.6 -0.5015406165,51.5107860084,609.6 -0.5062773666,51.50832866060001,609.6 -0.5106300405,51.5056089011,609.6 -0.5145615031,51.5026499783,609.6 -0.5180382389,51.49947718029999,609.6 -0.5210306378,51.4961176176,609.6 -0.5235132452,51.4925999902,609.6 -0.5254649770000001,51.4889543421,609.6 -0.526869296,51.4852118033,609.6 -0.5277143491,51.48140432329999,609.6 -0.5279930642,51.47756439840001,609.6 -0.5277032055999999,51.4737247933,609.6 -0.5268473884,51.4699182621,609.6 -0.5254330514,51.46617726860001,609.6 -0.5234723888,51.46253370969999,609.6 -0.5209822419,51.4590186443,609.6 -0.5179839515,51.4556620291,609.6 -0.5145031729,51.4524924637,609.6 -0.510569654,51.4495369488,609.6 -0.5062169801,51.4468206561,609.6 -0.5014822864,51.4443667159,609.6 -0.4964059411,51.4421960211,609.6 -0.4910312023,51.4403270501,609.6 -0.4854038501,51.4387757108,609.6 -0.479571799,51.4375552059,609.6 -0.4735846922,51.436675922,609.6 -0.4674934822,51.436145341,609.6 -0.46135,51.43596797760001,609.6 -0.4552065178,51.436145341,609.6 -0.4491153078,51.436675922,609.6 -0.443128201,51.4375552059,609.6 -0.4372961499,51.4387757108,609.6 -0.4316687977,51.4403270501,609.6 -0.4262940589,51.4421960211,609.6 -0.4212177136,51.4443667159,609.6 -0.4164830199,51.4468206561,609.6 -0.412130346,51.4495369488,609.6 -0.4081968271,51.4524924637,609.6 -0.4047160485,51.4556620291,609.6 -0.4017177581,51.4590186443,609.6 -0.3992276111999999,51.46253370969999,609.6 -0.3972669486000001,51.46617726860001,609.6 -0.3958526116,51.4699182621,609.6 -0.3949967944000001,51.4737247933,609.6 -0.3947069358,51.47756439840001,609.6 -0.3949856508999999,51.48140432329999,609.6 -0.395830704,51.4852118033,609.6 -0.3972350230000001,51.4889543421,609.6 -0.3991867548,51.4925999902,609.6 -0.4016693622,51.4961176176,609.6 -0.4046617611,51.49947718029999,609.6 -0.4081384969,51.5026499783,609.6 -0.4120699595000001,51.5056089011,609.6 -0.4164226334,51.50832866060001,609.6 -0.4211593835,51.5107860084,609.6 -0.4262397714,51.51295993590001,609.6 -0.4316204017,51.5148318544,609.6 -0.4372552934000001,51.5163857558,609.6 -0.4430962754,51.51760834980001,609.6 -0.4490934002,51.5184891791,609.6 -0.4551953742000001,51.5190207088,609.6 -0.46135,51.519198392,609.6 + + + + +
+ + EGRU128B LONDON HEATHROW RWY 09L + 512814N 0003325W -
512902N 0003325W -
512903N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512814N 0003137W -
512814N 0003325W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5569003333,51.4704933333,609.6 -0.5270472778,51.4706154722,609.6 -0.5277391047,51.473972328,609.6 -0.5279918993,51.4773531895,609.6 -0.527803899,51.4807356961,609.6 -0.52717625,51.48409747220001,609.6 -0.5570173333,51.48397538890001,609.6 -0.5569003333,51.4704933333,609.6 + + + + +
+ + EGRU128C LONDON HEATHROW RWY 27R + 512905N 0002141W -
512816N 0002141W -
512816N 0002344W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512904N 0002344W -
512905N 0002141W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3613735833,51.4846374722,609.6 -0.3956410556000001,51.4845450833,609.6 -0.3949547368,51.4811877781,609.6 -0.3947077047,51.4778067502,609.6 -0.3949014835999999,51.47442436730001,609.6 -0.3955346944,51.471063,609.6 -0.3612565833,51.47115541669999,609.6 -0.3613735833,51.4846374722,609.6 + + + + +
+ + EGRU128D LONDON HEATHROW RWY 09R + 512728N 0003315W -
512817N 0003316W -
512817N 0003138W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512729N 0003112W -
512728N 0003315W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.5542044167,51.45779225,609.6 -0.5200781389,51.4579273056,609.6 -0.5225554954,51.46113478249999,609.6 -0.5245850906,51.4644627941,609.6 -0.5261519863,51.4678869878,609.6 -0.5272446111,51.4713823056,609.6 -0.5543178889,51.47127436110001,609.6 -0.5542044167,51.45779225,609.6 + + + + +
+ + EGRU128E LONDON HEATHROW RWY 27L + 512819N 0002144W -
512730N 0002144W -
512730N 0002408W thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 512839N 0002741W to
512819N 0002343W -
512819N 0002144W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3622085,51.4719051944,609.6 -0.3953535278,51.4718188333,609.6 -0.3963867682,51.4683164757,609.6 -0.397895493,51.46488210049999,609.6 -0.3998685359,51.4615408393,609.6 -0.4022913611,51.4583171389,609.6 -0.3620950278,51.4584231111,609.6 -0.3622085,51.4719051944,609.6 + + + + +
+ + EGRU129A NORTHOLT + A circle, 2 NM radius, centred at 513310N 0002511W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4197222222,51.5860694194,609.6 -0.4252170924999999,51.58589284140001,609.6 -0.4306535891,51.5853649835,609.6 -0.4359739627,51.58449145300001,609.6 -0.4411217051,51.5832815289,609.6 -0.4460421536,51.5817480627,609.6 -0.4506830738000001,51.5799073411,609.6 -0.4549952171,51.5777789117,609.6 -0.4589328445,51.5753853748,609.6 -0.4624542133000001,51.5727521418,609.6 -0.4655220189,51.56990716420001,609.6 -0.4681037901,51.5668806359,609.6 -0.4701722306,51.5637046715,609.6 -0.4717055057,51.56041296439999,609.6 -0.4726874696,51.5570404286,609.6 -0.4731078322,51.5536228274,609.6 -0.4729622633,51.5501963944,609.6 -0.4722524326,51.5467974485,609.6 -0.4709859873,51.54346200929999,609.6 -0.4691764654,51.5402254156,609.6 -0.4668431476,51.53712195180001,609.6 -0.4640108489,51.53418448519999,609.6 -0.4607096516,51.5314441189,609.6 -0.4569745846,51.5289298638,609.6 -0.45284525,51.5266683326,609.6 -0.4483654033,51.5246834591,609.6 -0.4435824903,51.5229962465,609.6 -0.4385471456000001,51.521624546,609.6 -0.4333126589,51.5205828693,609.6 -0.4279344138,51.51988223559999,609.6 -0.4224693049,51.5195300562,609.6 -0.4169751395,51.5195300562,609.6 -0.4115100306,51.51988223559999,609.6 -0.4061317855,51.5205828693,609.6 -0.4008972988,51.521624546,609.6 -0.3958619541,51.5229962465,609.6 -0.3910790411,51.5246834591,609.6 -0.3865991945000001,51.5266683326,609.6 -0.3824698599,51.5289298638,609.6 -0.3787347928,51.5314441189,609.6 -0.3754335956,51.53418448519999,609.6 -0.3726012968,51.53712195180001,609.6 -0.3702679791,51.5402254156,609.6 -0.3684584571999999,51.54346200929999,609.6 -0.3671920117999999,51.5467974485,609.6 -0.3664821812,51.5501963944,609.6 -0.3663366122,51.5536228274,609.6 -0.3667569749,51.5570404286,609.6 -0.3677389388,51.56041296439999,609.6 -0.3692722138,51.5637046715,609.6 -0.3713406543,51.5668806359,609.6 -0.3739224255,51.56990716420001,609.6 -0.3769902312,51.5727521418,609.6 -0.3805115998999999,51.5753853748,609.6 -0.3844492274,51.5777789117,609.6 -0.3887613706,51.5799073411,609.6 -0.3934022908,51.5817480627,609.6 -0.3983227393,51.5832815289,609.6 -0.4034704818,51.58449145300001,609.6 -0.4087908553,51.5853649835,609.6 -0.414227352,51.58589284140001,609.6 -0.4197222222,51.5860694194,609.6 + + + + +
+ + EGRU129B NORTHOLT RWY 07 + 513150N 0002942W -
513221N 0003000W -
513244N 0002819W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513214N 0002801W -
513150N 0002942W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4949055556,51.5306527778,609.6 -0.466825,51.53710075,609.6 -0.4689011239999999,51.5398120238,609.6 -0.4705770388,51.54262895259999,609.6 -0.4718390278,51.5455286111,609.6 -0.4998722221999999,51.5390916667,609.6 -0.4949055556,51.5306527778,609.6 + + + + +
+ + EGRU129C NORTHOLT RWY 25 + 513430N 0002035W -
513400N 0002017W -
513335N 0002203W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513310N 0002511W to
513406N 0002221W -
513430N 0002035W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.3429888889,51.5750055556,609.6 -0.3724551111,51.5682804444,609.6 -0.3704066466,51.5655610198,609.6 -0.3687601003,51.5627375531,609.6 -0.3675288056,51.55983305560001,609.6 -0.3380138889,51.5665694444,609.6 -0.3429888889,51.5750055556,609.6 + + + + +
+ + EGRU131A ELSTREE + A circle, 2 NM radius, centred at 513921N 0001933W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.32585,51.68911605390001,609.6 -0.3313573375,51.68893947859999,609.6 -0.3368061684,51.68841162860001,609.6 -0.3421386119,51.6875381112,609.6 -0.3472980312,51.6863282054,609.6 -0.3522296393,51.68479476259999,609.6 -0.3568810829999999,51.6829540693,609.6 -0.3612030018,51.680825673,609.6 -0.365149553,51.6784321737,609.6 -0.3686788992,51.67579898259999,609.6 -0.3717536515000001,51.672954051,609.6 -0.3743412651,51.6699275723,609.6 -0.3764143825,51.66675166080001,609.6 -0.3779511197,51.66346000930001,609.6 -0.378935295,51.6600875314,609.6 -0.3793565956,51.6566699898,609.6 -0.3792106819,51.65324361759999,609.6 -0.3784992283,51.6498447329,609.6 -0.3772298997,51.6465093546,609.6 -0.3754162653999999,51.64327282090001,609.6 -0.3730776505000001,51.64016941549999,609.6 -0.3702389262,51.6372320048,609.6 -0.3669302437,51.6344916913,609.6 -0.3631867112000001,51.6319774852,609.6 -0.3590480206,51.62971599849999,609.6 -0.3545580267,51.62773116449999,609.6 -0.3497642823,51.62604398559999,609.6 -0.3447175366,51.6246723128,609.6 -0.3394711997,51.62363065710001,609.6 -0.3340807801,51.6229300376,609.6 -0.3286033007,51.62257786529999,609.6 -0.3230966993,51.62257786529999,609.6 -0.3176192199,51.6229300376,609.6 -0.3122288003,51.62363065710001,609.6 -0.3069824634,51.6246723128,609.6 -0.3019357177,51.62604398559999,609.6 -0.2971419733,51.62773116449999,609.6 -0.2926519794,51.62971599849999,609.6 -0.2885132888,51.6319774852,609.6 -0.2847697563,51.6344916913,609.6 -0.2814610738,51.6372320048,609.6 -0.2786223495,51.64016941549999,609.6 -0.2762837346,51.64327282090001,609.6 -0.2744701003,51.6465093546,609.6 -0.2732007717,51.6498447329,609.6 -0.2724893181,51.65324361759999,609.6 -0.2723434044,51.6566699898,609.6 -0.272764705,51.6600875314,609.6 -0.2737488803,51.66346000930001,609.6 -0.2752856175,51.66675166080001,609.6 -0.2773587349,51.6699275723,609.6 -0.2799463485,51.672954051,609.6 -0.2830211008,51.67579898259999,609.6 -0.286550447,51.6784321737,609.6 -0.2904969982,51.680825673,609.6 -0.294818917,51.6829540693,609.6 -0.2994703607,51.68479476259999,609.6 -0.3044019688,51.6863282054,609.6 -0.3095613881,51.6875381112,609.6 -0.3148938316,51.68841162860001,609.6 -0.3203426625,51.68893947859999,609.6 -0.32585,51.68911605390001,609.6 + + + + +
+ + EGRU131B ELSTREE RWY 08 + 513834N 0002401W -
513906N 0002410W -
513916N 0002246W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513844N 0002236W -
513834N 0002401W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.40025,51.6427944444,609.6 -0.3767162778,51.6454770833,609.6 -0.3780102409,51.64837118879999,609.6 -0.3788797193999999,51.6513260665,609.6 -0.3793175556,51.6543176667,609.6 -0.4028416667,51.6516361111,609.6 -0.40025,51.6427944444,609.6 + + + + +
+ + EGRU131C ELSTREE RWY 26 + 514008N 0001505W -
513936N 0001456W -
513926N 0001621W thence anti-clockwise by the arc of a circle radius 2 NM centred on 513921N 0001933W to
513958N 0001630W -
514008N 0001505W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.251425,51.66880833330001,609.6 -0.2749615278,51.6661527222,609.6 -0.2736733649,51.6632575555,609.6 -0.2728102231,51.6603019573,609.6 -0.2723790556,51.65731000000001,609.6 -0.2488333333,51.65996666670001,609.6 -0.251425,51.66880833330001,609.6 + + + + +
+ + EGRU135A LONDON CITY + A circle, 2 NM radius, centred at 513019N 0000319E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0551777778,51.5385224685,609.6 0.049688635,51.5383458893,609.6 0.04425780480000001,51.5378180277,609.6 0.0389429762,51.5369444912,609.6 0.0338005981,51.53573455860001,609.6 0.0288852764,51.5342010816,609.6 0.0242491907,51.5323603469,609.6 0.0199415384,51.53023190230001,609.6 0.0160080105,51.527838348,609.6 0.0124903067,51.5252050956,609.6 0.0094256923,51.5223600968,609.6 0.0068466052,51.5193335456,609.6 0.0047803132,51.5161575568,609.6 0.0032486287,51.512865824,609.6 0.0022676808,51.5094932614,609.6 0.001847749,51.5060756327,609.6 0.0019931596,51.50264917169999,609.6 0.0027022447,51.4992501975,609.6 0.0039673655,51.4959147301,609.6 0.005774998199999999,51.49267810879999,609.6 0.0081058824,51.489574618,609.6 0.0109352292,51.48663712559999,609.6 0.0142329877,51.4838967349,609.6 0.0179641657,51.4813824572,609.6 0.0220892021,51.4791209055,609.6 0.0265643871,51.4771360138,609.6 0.0313423241,51.47544878560001,609.6 0.0363724312,51.4740770724,609.6 0.0416014737,51.473035386,609.6 0.0469741258,51.4723347457,609.6 0.05243355169999999,51.471982563,609.6 0.0579220039,51.471982563,609.6 0.0633814298,51.4723347457,609.6 0.06875408180000001,51.473035386,609.6 0.0739831244,51.4740770724,609.6 0.07901323139999999,51.47544878560001,609.6 0.0837911685,51.4771360138,609.6 0.0882663534,51.4791209055,609.6 0.0923913899,51.4813824572,609.6 0.0961225678,51.4838967349,609.6 0.0994203263,51.48663712559999,609.6 0.1022496732,51.489574618,609.6 0.1045805574,51.49267810879999,609.6 0.1063881901,51.4959147301,609.6 0.1076533108,51.4992501975,609.6 0.1083623959,51.50264917169999,609.6 0.1085078065,51.5060756327,609.6 0.1080878748,51.5094932614,609.6 0.1071069268,51.512865824,609.6 0.1055752423,51.5161575568,609.6 0.1035089504,51.5193335456,609.6 0.1009298632,51.5223600968,609.6 0.09786524889999999,51.5252050956,609.6 0.094347545,51.527838348,609.6 0.0904140172,51.53023190230001,609.6 0.0861063648,51.5323603469,609.6 0.0814702792,51.5342010816,609.6 0.0765549574,51.53573455860001,609.6 0.0714125794,51.5369444912,609.6 0.06609775079999999,51.5378180277,609.6 0.06066692059999999,51.5383458893,609.6 0.0551777778,51.5385224685,609.6 + + + + +
+ + EGRU135B LONDON CITY RWY 09 + 513012N 0000136W -
513044N 0000133W -
513041N 0000010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513009N 0000007E -
513012N 0000136W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.0265288333,51.50327555559999,609.6 0.0020265,51.5023953889,609.6 0.0018316307,51.50539711759999,609.6 0.0020711489,51.5083975865,609.6 0.0027431944,51.5113723611,609.6 -0.0258050833,51.5122523333,609.6 -0.0265288333,51.50327555559999,609.6 + + + + +
+ + EGRU135C LONDON CITY RWY 27 + 513026N 0000814E -
512953N 0000811E -
512957N 0000627E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513019N 0000319E to
513029N 0000630E -
513026N 0000814E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1372346667,51.5071330556,609.6 0.1083335278,51.5080571389,609.6 0.1085236627,51.5050552868,609.6 0.1082794163,51.5020549588,609.6 0.1076028611,51.4990805833,609.6 0.136511,51.49815627780001,609.6 0.1372346667,51.5071330556,609.6 + + + + +
+ + EGRU136A STAPLEFORD + A circle, 2 NM radius, centred at 513909N 0000922E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1560083333,51.6857966284,609.6 0.1505013986,51.685620053,609.6 0.1450529662,51.68509220280001,609.6 0.1397209126,51.684218685,609.6 0.1345618705,51.68300877859999,609.6 0.129630623,51.681475335,609.6 0.1249795192,51.6796346408,609.6 0.1206579162,51.67750624340001,609.6 0.1167116533,51.6751127429,609.6 0.1131825649,51.67247955050001,609.6 0.110108037,51.6696346173,609.6 0.1075206121,51.66660813710001,609.6 0.1054476458,51.66343222390001,609.6 0.1039110205,51.6601405706,609.6 0.1029269166,51.6567680908,609.6 0.1025056463,51.6533505473,609.6 0.1026515488,51.6499241731,609.6 0.1033629501,51.6465252864,609.6 0.1046321855,51.6431899062,609.6 0.1064456869,51.6399533706,609.6 0.1087841307,51.6368499633,609.6 0.1116226474,51.63391255079999,609.6 0.1149310881,51.6311722356,609.6 0.1186743472,51.6286580279,609.6 0.1228127354,51.6263965398,609.6 0.1273024016,51.62441170450001,609.6 0.132095796,51.6227245245,609.6 0.1371421734,51.6213528508,609.6 0.1423881274,51.6203111944,609.6 0.1477781538,51.61961057449999,609.6 0.1532552335,51.61925840200001,609.6 0.1587614331,51.61925840200001,609.6 0.1642385129,51.61961057449999,609.6 0.1696285392,51.6203111944,609.6 0.1748744933,51.6213528508,609.6 0.1799208706,51.6227245245,609.6 0.1847142651,51.62441170450001,609.6 0.1892039312,51.6263965398,609.6 0.1933423195,51.6286580279,609.6 0.1970855786,51.6311722356,609.6 0.2003940193,51.63391255079999,609.6 0.2032325359,51.6368499633,609.6 0.2055709798,51.6399533706,609.6 0.2073844812,51.6431899062,609.6 0.2086537166,51.6465252864,609.6 0.2093651178,51.6499241731,609.6 0.2095110204,51.6533505473,609.6 0.2090897501,51.6567680908,609.6 0.2081056462,51.6601405706,609.6 0.2065690208,51.66343222390001,609.6 0.2044960546,51.66660813710001,609.6 0.2019086297,51.6696346173,609.6 0.1988341018,51.67247955050001,609.6 0.1953050134,51.6751127429,609.6 0.1913587504,51.67750624340001,609.6 0.1870371475,51.6796346408,609.6 0.1823860437,51.681475335,609.6 0.1774547962,51.68300877859999,609.6 0.172295754,51.684218685,609.6 0.1669637005,51.68509220280001,609.6 0.161515268,51.685620053,609.6 0.1560083333,51.6857966284,609.6 + + + + +
+ + EGRU136B STAPLEFORD RWY 03L + 513634N 0000654E -
513653N 0000612E -
513743N 0000708E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513724N 0000750E -
513634N 0000654E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.114975,51.6095305556,609.6 0.1306218889,51.62320063889999,609.6 0.1264803317,51.6247434871,609.6 0.1225788083,51.62651232070001,609.6 0.1189490556,51.62849275,609.6 0.1032222222,51.61475,609.6 0.114975,51.6095305556,609.6 + + + + +
+ + EGRU136C STAPLEFORD RWY 21R + 514140N 0001141E -
514122N 0001223E -
514037N 0001132E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514056N 0001050E -
514140N 0001141E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1946944444,51.6945361111,609.6 0.1804416944,51.6821273889,609.6 0.1846372067,51.6806366835,609.6 0.1885991606,51.6789167892,609.6 0.1922952778,51.67698175,609.6 0.2064694444,51.6893194444,609.6 0.1946944444,51.6945361111,609.6 + + + + +
+ + EGRU136D STAPLEFORD RWY 03R + 513634N 0000656E -
513652N 0000613E -
513742N 0000710E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
513723N 0000752E -
513634N 0000656E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1154222222,51.6093166667,609.6 0.1311190278,51.62303599999999,609.6 0.126951311,51.6245517675,609.6 0.1230198351,51.6262951166,609.6 0.1193565833,51.6282518611,609.6 0.1036666667,51.61453611109999,609.6 0.1154222222,51.6093166667,609.6 + + + + +
+ + EGRU136E STAPLEFORD RWY 21L + 514140N 0001143E -
514121N 0001225E -
514036N 0001134E thence anti-clockwise by the arc of a circle radius 2 NM centred on 513909N 0000922E to
514055N 0001051E -
514140N 0001143E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1951388889,51.6943527778,609.6 0.1809234167,51.68197180559999,609.6 0.1850942614,51.6804547511,609.6 0.1890278444,51.678710016,609.6 0.1926921111,51.67675183330001,609.6 0.2069138889,51.6891361111,609.6 0.1951388889,51.6943527778,609.6 + + + + +
+ + EGRU137A LONDON STANSTED + A circle, 2.5 NM radius, centred at 515306N 0001406E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.235,51.9266121564,609.6 0.2287898076,51.92643448310001,609.6 0.2226327443,51.92590298339999,609.6 0.2165814812,51.9250222041,609.6 0.2106877765,51.9237996799,609.6 0.2050020304,51.9222458679,609.6 0.1995728501,51.92037405800001,609.6 0.1944466326,51.9182002582,609.6 0.1896671656,51.9157430564,609.6 0.1852752525,51.9130234609,609.6 0.1813083633,51.9100647192,609.6 0.1778003149,51.90689211849999,609.6 0.1747809834,51.9035327683,609.6 0.1722760514,51.9000153673,609.6 0.1703067912,51.896369958,609.6 0.1688898867,51.8926276688,609.6 0.1680372953,51.8888204475,609.6 0.1677561503,51.8849807881,609.6 0.1680487046,51.8811414532,609.6 0.1689123167,51.87733519460001,609.6 0.1703394781,51.8735944735,609.6 0.1723178822,51.8699511843,609.6 0.1748305335,51.8664363832,609.6 0.1778558969,51.86308002400001,609.6 0.1813680845,51.8599107037,609.6 0.1853370792,51.85695542020001,609.6 0.1897289923,51.8542393427,609.6 0.1945063538,51.851785599,609.6 0.1996284322,51.8496150796,609.6 0.2050515805,51.84774626079999,609.6 0.2107296074,51.84619504860001,609.6 0.2166141682,51.8449746444,609.6 0.2226551744,51.8440954332,609.6 0.2288012169,51.8435648963,609.6 0.235,51.8433875477,609.6 0.2411987831,51.8435648963,609.6 0.2473448256,51.8440954332,609.6 0.2533858318,51.8449746444,609.6 0.2592703926,51.84619504860001,609.6 0.2649484195,51.84774626079999,609.6 0.2703715678,51.8496150796,609.6 0.2754936462,51.851785599,609.6 0.2802710077,51.8542393427,609.6 0.2846629208,51.85695542020001,609.6 0.2886319155,51.8599107037,609.6 0.2921441031,51.86308002400001,609.6 0.2951694665,51.8664363832,609.6 0.2976821178,51.8699511843,609.6 0.2996605219,51.8735944735,609.6 0.3010876833,51.87733519460001,609.6 0.3019512954,51.8811414532,609.6 0.3022438497,51.8849807881,609.6 0.3019627047,51.8888204475,609.6 0.3011101133,51.8926276688,609.6 0.2996932088,51.896369958,609.6 0.2977239486,51.9000153673,609.6 0.2952190166,51.9035327683,609.6 0.2921996851,51.90689211849999,609.6 0.2886916367,51.9100647192,609.6 0.2847247475,51.9130234609,609.6 0.2803328344,51.9157430564,609.6 0.2755533674,51.9182002582,609.6 0.2704271499,51.92037405800001,609.6 0.2649979696,51.9222458679,609.6 0.2593122235,51.9237996799,609.6 0.2534185188,51.9250222041,609.6 0.2473672557,51.92590298339999,609.6 0.2412101924,51.92643448310001,609.6 0.235,51.9266121564,609.6 + + + + +
+ + EGRU137B LONDON STANSTED RWY 04 + 515028N 0001044E -
515050N 0001005E -
515128N 0001103E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515106N 0001141E -
515028N 0001044E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.1788194444,51.8410361111,609.6 0.1947456944,51.85167430559999,609.6 0.1909710506,51.8535562167,609.6 0.187424914,51.8556015888,609.6 0.1841257222,51.85779980560001,609.6 0.1681888889,51.84715277780001,609.6 0.1788194444,51.8410361111,609.6 + + + + +
+ + EGRU137C LONDON STANSTED RWY 22 + 515552N 0001739E -
515530N 0001817E -
515444N 0001709E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 515306N 0001406E to
515506N 0001630E -
515552N 0001739E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.2941833333,51.93113055560001,609.6 0.2750736667,51.9184224444,609.6 0.2788639154,51.916548197,609.6 0.2824255347,51.9145097839,609.6 0.28574,51.91231783329999,609.6 0.3048388889,51.9250166667,609.6 0.2941833333,51.93113055560001,609.6 + + + + +
+ + EGRU138A ANDREWSFIELD + A circle, 2 NM radius, centred at 515342N 0002657E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4491666667,51.9282896919,609.6 0.4436301033,51.9281131227,609.6 0.4381523581,51.927585291,609.6 0.4327916200999999,51.926711804,609.6 0.4276048275,51.9255019406,609.6 0.422647059,51.9239685519,609.6 0.4179709460000001,51.92212792399999,609.6 0.4136261113,51.9199996043,609.6 0.4096586409,51.91760619210001,609.6 0.4061105941,51.9149730981,609.6 0.4030195576,51.9121282729,609.6 0.4004182481,51.90910190909999,609.6 0.3983341674,51.90592612,609.6 0.3967893144,51.9026345974,609.6 0.3957999552,51.8992622536,609.6 0.3953764561,51.89584485030001,609.6 0.3955231779999999,51.8924186188,609.6 0.3962384364,51.88901987600001,609.6 0.3975145241,51.88568463899999,609.6 0.3993377987,51.8824482445,609.6 0.4016888316,51.8793449744,609.6 0.4045426185,51.8764076934,609.6 0.4078688481,51.8736675024,609.6 0.4116322255,51.87115341000001,609.6 0.4157928483000001,51.86889202660001,609.6 0.4203066295,51.86690728399999,609.6 0.4251257647,51.86522018340001,609.6 0.4301992364,51.86384857459999,609.6 0.4354733526,51.86280696779999,609.6 0.4408923116999999,51.8621063813,609.6 0.4463987897999999,51.8617542257,609.6 0.4519345435,51.8617542257,609.6 0.4574410216,51.8621063813,609.6 0.4628599807,51.86280696779999,609.6 0.4681340969,51.86384857459999,609.6 0.4732075687,51.86522018340001,609.6 0.4780267038,51.86690728399999,609.6 0.4825404851000001,51.86889202660001,609.6 0.4867011077999999,51.87115341000001,609.6 0.4904644852,51.8736675024,609.6 0.4937907147999999,51.8764076934,609.6 0.4966445018,51.8793449744,609.6 0.4989955347,51.8824482445,609.6 0.5008188092,51.88568463899999,609.6 0.502094897,51.88901987600001,609.6 0.5028101553,51.8924186188,609.6 0.5029568773,51.89584485030001,609.6 0.5025333781,51.8992622536,609.6 0.5015440189,51.9026345974,609.6 0.4999991659,51.90592612,609.6 0.4979150853,51.90910190909999,609.6 0.4953137757,51.9121282729,609.6 0.4922227392,51.9149730981,609.6 0.4886746924,51.91760619210001,609.6 0.484707222,51.9199996043,609.6 0.4803623874,51.92212792399999,609.6 0.4756862743,51.9239685519,609.6 0.4707285057999999,51.9255019406,609.6 0.4655417132,51.926711804,609.6 0.4601809752,51.927585291,609.6 0.45470323,51.9281131227,609.6 0.4491666667,51.9282896919,609.6 + + + + +
+ + EGRU138B ANDREWSFIELD RWY 09L + 515311N 0002223E -
515343N 0002219E -
515348N 0002344E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515316N 0002348E -
515311N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3730888889,51.8864027778,609.6 0.3966865556,51.88766425,609.6 0.3958296993000001,51.89062131390001,609.6 0.3954070986,51.89361413149999,609.6 0.3954222778,51.8966183333,609.6 0.3718527778,51.8953583333,609.6 0.3730888889,51.8864027778,609.6 + + + + +
+ + EGRU138C ANDREWSFIELD RWY 27R + 515413N 0003137E -
515341N 0003142E -
515336N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515408N 0003006E -
515413N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5269916667,51.9035638889,609.6 0.5016900556,51.9022398056,609.6 0.5025295237,51.89928078159999,609.6 0.502934256,51.89628698540001,609.6 0.5029010556,51.8932828056,609.6 0.5282305556,51.89460833329999,609.6 0.5269916667,51.9035638889,609.6 + + + + +
+ + EGRU138D ANDREWSFIELD RWY 09R + 515310N 0002223E -
515342N 0002218E -
515347N 0002343E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515315N 0002348E -
515310N 0002223E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.3729722222,51.8861333333,609.6 0.3967850555999999,51.8873999167,609.6 0.3958892902,51.8903525916,609.6 0.3954272954,51.89334320879999,609.6 0.3954029167000001,51.8963474167,609.6 0.3717416667,51.8950888889,609.6 0.3729722222,51.8861333333,609.6 + + + + +
+ + EGRU138E ANDREWSFIELD RWY 27L + 515412N 0003137E -
515340N 0003142E -
515335N 0003010E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515342N 0002657E to
515407N 0003006E -
515412N 0003137E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5270416667,51.9032611111,609.6 0.50179325,51.90194663890001,609.6 0.502589532,51.8989830515,609.6 0.5029506279,51.8959871214,609.6 0.5028736667,51.89298324999999,609.6 0.5282722222,51.8943055556,609.6 0.5270416667,51.9032611111,609.6 + + + + +
+ + EGRU141A EARLS COLNE + A circle, 2 NM radius, centred at 515452N 0004057E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6825,51.9477340257,609.6 0.6769610427,51.947557457,609.6 0.6714809291,51.9470296268,609.6 0.6661178735,51.9461561423,609.6 0.6609288387,51.94494628230001,609.6 0.6559689273,51.94341289800001,609.6 0.6512907936,51.94157227549999,609.6 0.6469440818,51.9394439619,609.6 0.6429748979,51.9370505568,609.6 0.6394253193,51.93441747070001,609.6 0.636332949,51.9315726541,609.6 0.6337305176,51.9285462996,609.6 0.631645539,51.9253705205,609.6 0.6301000212,51.9220790084,609.6 0.6291102374,51.9187066755,609.6 0.6286865582,51.9152892834,609.6 0.6288333463,51.9118630633,609.6 0.6295489163,51.908464332,609.6 0.6308255577,51.90512910650001,609.6 0.632649622,51.9018927233,609.6 0.635001672,51.8987894642,609.6 0.6378566928,51.8958521937,609.6 0.6411843597,51.8931120127,609.6 0.6449493626,51.8905979296,609.6 0.6491117818,51.8883365545,609.6 0.6536275115,51.8863518193,609.6 0.6584487265,51.8846647251,609.6 0.6635243874,51.8832931215,609.6 0.668800779,51.8822515187,609.6 0.6742220758,51.8815509349,609.6 0.6797309292,51.8811987806,609.6 0.6852690708,51.8811987806,609.6 0.6907779241999999,51.8815509349,609.6 0.696199221,51.8822515187,609.6 0.7014756126,51.8832931215,609.6 0.7065512735000001,51.8846647251,609.6 0.7113724885,51.8863518193,609.6 0.7158882182,51.8883365545,609.6 0.7200506374,51.8905979296,609.6 0.7238156403,51.8931120127,609.6 0.7271433072,51.8958521937,609.6 0.729998328,51.8987894642,609.6 0.7323503780000001,51.9018927233,609.6 0.7341744422999998,51.90512910650001,609.6 0.7354510837,51.908464332,609.6 0.7361666536999999,51.9118630633,609.6 0.7363134417999999,51.9152892834,609.6 0.7358897625999999,51.9187066755,609.6 0.7348999788,51.9220790084,609.6 0.733354461,51.9253705205,609.6 0.7312694824,51.9285462996,609.6 0.728667051,51.9315726541,609.6 0.7255746807,51.93441747070001,609.6 0.7220251021,51.9370505568,609.6 0.7180559182000001,51.9394439619,609.6 0.7137092064,51.94157227549999,609.6 0.7090310727,51.94341289800001,609.6 0.7040711613,51.94494628230001,609.6 0.6988821265,51.9461561423,609.6 0.6935190709,51.9470296268,609.6 0.6880389573,51.947557457,609.6 0.6825,51.9477340257,609.6 + + + + +
+ + EGRU141B EARLS COLNE RWY 06 + 515309N 0003708E -
515337N 0003642E -
515405N 0003759E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515337N 0003826E -
515309N 0003708E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6188194444,51.8858888889,609.6 0.6405008056,51.89362883329999,609.6 0.6376370069,51.8960555344,609.6 0.6351382452,51.8986320512,609.6 0.6330249167000001,51.90133741670001,609.6 0.6115694444000001,51.8936777778,609.6 0.6188194444,51.8858888889,609.6 + + + + +
+ + EGRU141C EARLS COLNE RWY 24 + 515631N 0004450E -
515603N 0004516E -
515535N 0004358E thence anti-clockwise by the arc of a circle radius 2 NM centred on 515452N 0004057E to
515604N 0004332E -
515631N 0004450E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7473027778,51.94202500000001,609.6 0.7256713333,51.9343375,609.6 0.7283957123,51.9318493242,609.6 0.7307458014,51.9292193892,609.6 0.7327025,51.92646913890001,609.6 0.7545583333,51.93423611109999,609.6 0.7473027778,51.94202500000001,609.6 + + + + +
+ + EGRU142A SOUTHEND + A circle, 2.5 NM radius, centred at 513413N 0004136E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6933333333,51.6118921753,609.6 0.6871661804,51.6117144943,609.6 0.6810517867,51.6111829714,609.6 0.6750424567,51.6103021536,609.6 0.6691895887,51.6090795755,609.6 0.6635432321,51.6075256945,609.6 0.6581516565,51.60565380079999,609.6 0.6530609364,51.6034799024,609.6 0.648314556,51.6010225879,609.6 0.6439530358,51.5983028658,609.6 0.6400135863999999,51.5953439844,609.6 0.6365297913,51.5921712314,609.6 0.6335313205000001,51.5888117171,609.6 0.63104368,51.5852941413,609.6 0.6290879964,51.5816485477,609.6 0.62768084,51.5779060657,609.6 0.6268340873,51.5740986447,609.6 0.6265548244,51.5702587803,609.6 0.6268452906,51.5664192368,609.6 0.6277028650000001,51.5626127676,609.6 0.6291200932,51.5588718361,609.6 0.6310847554,51.5552283386,609.6 0.6335799758,51.5517133334,609.6 0.6365843696,51.54835677650001,609.6 0.6400722293,51.5451872669,609.6 0.6440137460000001,51.5422318046,609.6 0.6483752663,51.53951556090001,609.6 0.6531195793,51.5370616655,609.6 0.6582062349,51.5348910106,609.6 0.6635918876,51.5330220742,609.6 0.6692306642,51.5314707638,609.6 0.6750745535,51.5302502819,609.6 0.6810738118,51.5293710145,609.6 0.6871773836,51.5288404435,609.6 0.6933333333,51.5286630835,609.6 0.699489283,51.5288404435,609.6 0.7055928549,51.5293710145,609.6 0.7115921131,51.5302502819,609.6 0.7174360023999999,51.5314707638,609.6 0.7230747791000001,51.5330220742,609.6 0.7284604317,51.5348910106,609.6 0.7335470874,51.5370616655,609.6 0.7382914004,51.53951556090001,609.6 0.7426529206000001,51.5422318046,609.6 0.7465944374000001,51.5451872669,609.6 0.7500822969999998,51.54835677650001,609.6 0.7530866907999999,51.5517133334,609.6 0.7555819112,51.5552283386,609.6 0.7575465735,51.5588718361,609.6 0.7589638016,51.5626127676,609.6 0.7598213761,51.5664192368,609.6 0.7601118423,51.5702587803,609.6 0.7598325793,51.5740986447,609.6 0.7589858267,51.5779060657,609.6 0.7575786702,51.5816485477,609.6 0.7556229865999999,51.5852941413,609.6 0.7531353462,51.5888117171,609.6 0.7501368754,51.5921712314,609.6 0.7466530802,51.5953439844,609.6 0.7427136308999999,51.5983028658,609.6 0.7383521107,51.6010225879,609.6 0.7336057302,51.6034799024,609.6 0.7285150102,51.60565380079999,609.6 0.7231234345000001,51.6075256945,609.6 0.7174770779,51.6090795755,609.6 0.7116242099,51.6103021536,609.6 0.7056148799,51.6111829714,609.6 0.6995004862999999,51.6117144943,609.6 0.6933333333,51.6118921753,609.6 + + + + +
+ + EGRU142B SOUTHEND RWY 05 + 513209N 0003745E -
513236N 0003714E -
513259N 0003807E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513233N 0003837E -
513209N 0003745E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.6291166667,51.53595555559999,609.6 0.6436260556,51.54249894439999,609.6 0.6405434667,51.544803412,609.6 0.637734927,51.5472403342,609.6 0.6352150556,51.5497970556,609.6 0.6206805556,51.5432416667,609.6 0.6291166667,51.53595555559999,609.6 + + + + +
+ + EGRU142C SOUTHEND RWY 23 + 513615N 0004523E -
513549N 0004553E -
513527N 0004505E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 513413N 0004136E to
513554N 0004434E -
513615N 0004523E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.7563638888999999,51.6042944444,609.6 0.7428335,51.5982206389,609.6 0.7459369184,51.5959248333,609.6 0.7487662855,51.5934956228,609.6 0.7513069167,51.5909456667,609.6 0.7648138889000001,51.5970083333,609.6 0.7563638888999999,51.6042944444,609.6 + + + + +
+ + EGRU143A LONDON HELIPORT + A circle, 2 NM radius, centred at 512812N 0001046W
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the heliport operator. For contact details see AIP, Part 3 - Heliports, Section AD 3.2 ]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1795388889,51.50322266999999,609.6 -0.1850237897,51.5030460899,609.6 -0.1904504231,51.5025182256,609.6 -0.1957611449,51.5016446845,609.6 -0.2008995498,51.5004347457,609.6 -0.2058110744,51.4989012607,609.6 -0.2104435795,51.4970605163,609.6 -0.2147479056,51.4949320603,609.6 -0.2186783971,51.49253849309999,609.6 -0.2221933866,51.4899052263,609.6 -0.2252556374,51.4870602117,609.6 -0.2278327366,51.4840336435,609.6 -0.2298974372,51.48085763660001,609.6 -0.2314279437,51.47756588469999,609.6 -0.2324081392,51.4741933023,609.6 -0.2328277518,51.4707756531,609.6 -0.2326824584,51.46734917130001,609.6 -0.2319739255,51.46395017609999,609.6 -0.2307097858,51.4606146879,609.6 -0.2289035523,51.4573780459,609.6 -0.2265744705,51.4542745352,609.6 -0.22374731,51.4513370235,609.6 -0.2204520984,51.4485966148,609.6 -0.2167238008,51.4460823203,609.6 -0.2126019478,51.44382075330001,609.6 -0.2081302155,51.44183584809999,609.6 -0.2033559639,51.4401486084,609.6 -0.1983297361,51.4387768857,609.6 -0.1931047256,51.43773519200001,609.6 -0.187736216,51.4370345469,609.6 -0.1822809993,51.4366823617,609.6 -0.1767967785,51.4366823617,609.6 -0.1713415617,51.4370345469,609.6 -0.1659730521,51.43773519200001,609.6 -0.1607480417,51.4387768857,609.6 -0.1557218139,51.4401486084,609.6 -0.1509475623,51.44183584809999,609.6 -0.14647583,51.44382075330001,609.6 -0.142353977,51.4460823203,609.6 -0.1386256794,51.4485966148,609.6 -0.1353304678,51.4513370235,609.6 -0.1325033072,51.4542745352,609.6 -0.1301742255,51.4573780459,609.6 -0.128367992,51.4606146879,609.6 -0.1271038523,51.46395017609999,609.6 -0.1263953194,51.46734917130001,609.6 -0.126250026,51.4707756531,609.6 -0.1266696386,51.4741933023,609.6 -0.1276498341,51.47756588469999,609.6 -0.1291803406,51.48085763660001,609.6 -0.1312450412,51.4840336435,609.6 -0.1338221404,51.4870602117,609.6 -0.1368843911,51.4899052263,609.6 -0.1403993807,51.49253849309999,609.6 -0.1443298721,51.4949320603,609.6 -0.1486341983,51.4970605163,609.6 -0.1532667033,51.4989012607,609.6 -0.158178228,51.5004347457,609.6 -0.1633166329,51.5016446845,609.6 -0.1686273547,51.5025182256,609.6 -0.1740539881,51.5030460899,609.6 -0.1795388889,51.50322266999999,609.6 + + + + +
+ + EGRU151 HMP BELMARSH/THAMESIDE/ISIS + 513012N 0000557E -
512942N 0000624E -
512930N 0000550E -
512918N 0000540E -
512927N 0000450E -
512952N 0000501E -
513012N 0000557E
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 16 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.0990305556,51.5032916667,152.4 0.08349444440000001,51.4976583333,152.4 0.08043333330000001,51.4909166667,152.4 0.0945611111,51.4882305556,152.4 0.097125,51.4915305556,152.4 0.1065527778,51.4949638889,152.4 0.0990305556,51.5032916667,152.4 + + + + +
+ + EGRU153 HMP BRIXTON + 512722N 0000738W -
512718N 0000710W -
512709N 0000703W -
512656N 0000707W -
512650N 0000721W -
512653N 0000755W -
512714N 0000758W -
512722N 0000738W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 125 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1273222222,51.4562194444,182.88 -0.132775,51.4538527778,182.88 -0.132025,51.4481638889,182.88 -0.1223611111,51.4472388889,182.88 -0.1186333333,51.4488194444,182.88 -0.1174055556,51.4525472222,182.88 -0.1195583333,51.4551111111,182.88 -0.1273222222,51.4562194444,182.88 + + + + +
+ + EGRU154 HMP BRONZEFIELD + 512610N 0002935W -
512618N 0002841W -
512554N 0002832W -
512544N 0002845W -
512541N 0002907W -
512549N 0002925W -
512610N 0002935W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 53 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4930166667,51.4362277778,152.4 -0.4903944444,51.4301416667,152.4 -0.4851722222,51.42807222220001,152.4 -0.4792944444,51.4289388889,152.4 -0.4755583333,51.43160277779999,152.4 -0.4780916667,51.4384027778,152.4 -0.4930166667,51.4362277778,152.4 + + + + +
+ + EGRU157 HMP CHELMSFORD + 514431N 0002858E -
514416N 0002945E -
514359N 0002948E -
514351N 0002936E -
514352N 0002909E -
514404N 0002833E -
514431N 0002858E
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 135 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.4828416667,51.74201111109999,182.88 0.4758444444,51.73457222220001,182.88 0.4857611110999999,51.73124444439999,182.88 0.4934583333,51.7308777778,182.88 0.4965583332999999,51.7330944444,182.88 0.4958222222,51.7377777778,182.88 0.4828416667,51.74201111109999,182.88 + + + + +
+ + EGRU163 HMP FELTHAM + 512644N 0002615W -
512640N 0002532W -
512559N 0002547W -
512607N 0002647W -
512639N 0002641W -
512644N 0002615W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by Non-Standard Flight Applications (NSF NATS) and HMPPS.
NSF: Online Application: https://nsf.nats.aero/drones-and-model-aircraft/
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 62 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.4374555555999999,51.4456916667,152.4 -0.4445888889,51.4440722222,152.4 -0.4464194444,51.4351611111,152.4 -0.4298361111,51.4329861111,152.4 -0.4255777777999999,51.4443638889,152.4 -0.4374555555999999,51.4456916667,152.4 + + + + +
+ + EGRU168 HMP PENTONVILLE + 513256N 0000726W -
513258N 0000659W -
513257N 0000641W -
513231N 0000624W -
513222N 0000721W -
513256N 0000726W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 141 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1238444444,51.54883611109999,182.88 -0.1224222222,51.5393944444,182.88 -0.1066055556,51.54205,182.88 -0.1114833333,51.5491972222,182.88 -0.1164833333,51.5494138889,182.88 -0.1238444444,51.54883611109999,182.88 + + + + +
+ + EGRU175 HMP WANDSWORTH + 512722N 0001030W -
512653N 0001006W -
512636N 0001042W -
512659N 0001111W -
512714N 0001056W -
512722N 0001030W
Upper limit: 600 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by London Heliport (FRZ - EGRU143A) and HMPPS.
London Heliport 020-7228 0181 or email: Info@londonheliport.co.uk
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 112 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.1751111111,51.4561361111,182.88 -0.1822138889,51.45391944440001,182.88 -0.1864583333,51.4496,182.88 -0.1783527778,51.4432166667,182.88 -0.1683916667,51.4481388889,182.88 -0.1751111111,51.4561361111,182.88 + + + + +
+ + EGRU177 HMP WORMWOOD SCRUBS + 513116N 0001456W -
513119N 0001401W -
513047N 0001352W -
513044N 0001445W -
513057N 0001454W -
513116N 0001456W
Upper limit: 500 FT MSL
Lower limit: SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 51 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + -0.2490222222,51.52105277780001,152.4 -0.2482861111,51.5157277778,152.4 -0.245725,51.51224999999999,152.4 -0.2311805556,51.513125,152.4 -0.2334805556,51.5218972222,152.4 -0.2490222222,51.52105277780001,152.4 + + + + +
+ + EGRU230A WATTISHAM + A circle, 2.5 NM radius, centred at 520737N 0005719E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.9554138889,52.1686382148,609.6 0.9491700573,52.16846054749999,609.6 0.9429796438999999,52.16792906549999,609.6 0.9368956062,52.1670483157,609.6 0.9309699841,52.1658258326,609.6 0.9252534515999999,52.1642720733,609.6 0.91979488,52.1624003276,609.6 0.9146409181999999,52.1602266031,609.6 0.9098355913,52.15776948760001,609.6 0.9054199238000001,52.155049989,609.6 0.9014315882,52.1520913543,609.6 0.8979045841,52.1489188703,609.6 0.8948689485,52.1455596457,609.6 0.8923505021,52.1420423786,609.6 0.8903706309,52.13839711069999,609.6 0.8889461078999999,52.1346549692,609.6 0.8880889534999999,52.130847901,609.6 0.887806338,52.1270083989,609.6 0.8881005247,52.1231692242,609.6 0.8889688560999999,52.1193631272,609.6 0.8904037816000001,52.1156225676,609.6 0.8923929263000001,52.1119794383,609.6 0.8949192016,52.1084647939,609.6 0.8979609547000001,52.1051085866,609.6 0.9014921567,52.1019394118,609.6 0.9054826276,52.0989842656,609.6 0.9098982951,52.0962683158,609.6 0.9147014867,52.09381468880001,609.6 0.9198512507,52.0916442735,609.6 0.9253037047,52.0897755451,609.6 0.9310124084,52.0882244085,609.6 0.9369287568999999,52.087004064,609.6 0.9430023922,52.0861248961,609.6 0.9491816283999999,52.0855943853,609.6 0.9554138889,52.0854170454,609.6 0.9616461494,52.0855943853,609.6 0.9678253855999999,52.0861248961,609.6 0.9738990208,52.087004064,609.6 0.9798153694,52.0882244085,609.6 0.9855240730999999,52.0897755451,609.6 0.9909765270999999,52.0916442735,609.6 0.9961262910000002,52.09381468880001,609.6 1.0009294826,52.0962683158,609.6 1.0053451502,52.0989842656,609.6 1.0093356211,52.1019394118,609.6 1.0128668231,52.1051085866,609.6 1.0159085762,52.1084647939,609.6 1.0184348515,52.1119794383,609.6 1.0204239962,52.1156225676,609.6 1.0218589216,52.1193631272,609.6 1.0227272531,52.1231692242,609.6 1.0230214398,52.1270083989,609.6 1.0227388243,52.130847901,609.6 1.0218816699,52.1346549692,609.6 1.0204571469,52.13839711069999,609.6 1.0184772757,52.1420423786,609.6 1.0159588292,52.1455596457,609.6 1.0129231937,52.1489188703,609.6 1.0093961896,52.1520913543,609.6 1.005407854,52.155049989,609.6 1.0009921865,52.15776948760001,609.6 0.9961868596,52.1602266031,609.6 0.9910328978,52.1624003276,609.6 0.9855743262,52.1642720733,609.6 0.9798577937,52.1658258326,609.6 0.9739321716,52.1670483157,609.6 0.9678481339,52.16792906549999,609.6 0.9616577205,52.16846054749999,609.6 0.9554138889,52.1686382148,609.6 + + + + +
+ + EGRU230B WATTISHAM RWY 05 + 520513N 0005340E -
520537N 0005305E -
520609N 0005402E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520545N 0005438E -
520513N 0005340E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.8945785833,52.08708213889999,609.6 0.9104756667,52.09594825,609.6 0.9069544023,52.0980224587,609.6 0.9036846797,52.10024747229999,609.6 0.9006835277999999,52.10261175,609.6 0.8847938611,52.0937486944,609.6 0.8945785833,52.08708213889999,609.6 + + + + +
+ + EGRU230C WATTISHAM RWY 23 + 521004N 0010104E -
520940N 0010139E -
520905N 0010037E thence anti-clockwise by the arc of a circle radius 2.5 NM centred on 520737N 0005719E to
520929N 0010001E -
521004N 0010104E
Upper limit: 2000 FT SFC
Lower limit: SFC
Class: FRZ Active H24. Unmanned aircraft flight not permitted unless permission has been granted by the relevant Air Traffic Service unit or aerodrome operator. For contact details see AIP, Part 3 - Aerodromes, Section AD 2.2]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.0178328056,52.16778141670001,609.6 1.0003954167,52.1581005278,609.6 1.0039183892,52.1560243877,609.6 1.0071885817,52.15379737890001,609.6 1.010189,52.1514311111,609.6 1.0276337778,52.1611149444,609.6 1.0178328056,52.16778141670001,609.6 + + + + +
+ + EGRU246 HMP HIGHPOINT + 520847N 0003034E -
520845N 0003109E -
520801N 0003134E -
520749N 0003019E -
520822N 0003003E -
520847N 0003034E
Upper limit: 800 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 390 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 0.5095194444,52.1464944444,243.84 0.5008166667,52.1393277778,243.84 0.5051555556,52.1304,243.84 0.5260694444,52.1337222222,243.84 0.5192861111,52.1459222222,243.84 0.5095194444,52.1464944444,243.84 + + + + +
+ + EGRU258 HMP WARREN HILL + 520356N 0012736E -
520335N 0012812E -
520319N 0012809E -
520307N 0012727E -
520333N 0012659E -
520356N 0012736E
Upper limit: 500 FT MSL
Lower limit: 0 FT SFC
Class: HMP Restricted airspace active H24.
Unmanned aircraft flight not permitted unless permission has been granted by HMPPS.
HMPPS email: drone.RFZapplication@justice.gov.uk
SI 2023/1101
Site elevation: 59 FT AMSL]]>
+ #rdpStyleMap + + 1 + 1 + relativeToGround + + + relativeToGround + + 1.4600444444,52.06553888890001,152.4 1.449675,52.0590805556,152.4 1.4574888889,52.0519277778,152.4 1.4692555556,52.0552388889,152.4 1.4700805556,52.05961666670001,152.4 1.4600444444,52.06553888890001,152.4 + + + + +
+
+
+
+
diff --git a/PathPlanning/DynamicWindowApproach/Fences.tsp b/PathPlanning/DynamicWindowApproach/Fences.tsp new file mode 100644 index 0000000000..17c7f21e86 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Fences.tsp @@ -0,0 +1,1206 @@ +NAME: example +TYPE: TSP +DIMENSION: 1200 +EDGE_WEIGHT_TYPE: EUC_2D +NODE_COORD_SECTION +1 51.5380555556 0.8011111111 +2 51.5083333333 0.7833333333 +3 51.50472222219999 0.8511111111000002 +4 51.5380555556 0.8011111111 +5 51.6666666667 1.0666666667 +6 51.6205555556 0.9266666667 +7 51.6205555556 1.2008333333 +8 51.6666666667 1.2702777778 +9 51.6666666667 1.0666666667 +10 51.7 1.19 +11 51.6666666667 1.0666666667 +12 51.6666666667 1.2702777778 +13 51.7 1.32 +14 51.7 1.19 +15 51.6166666667 0.9152777778000001 +16 51.5955555556 0.9388888889 +17 51.6105555556 0.9805555555999999 +18 51.63194444440001 0.9611111111 +19 51.6166666667 0.9152777778000001 +20 51.6205555556 0.9266666667 +21 51.6166666667 0.9152777778000001 +22 51.61495 0.915875 +23 51.6141194444 0.913075 +24 51.61360000000001 0.9085638889 +25 51.61410277779999 0.9064277778 +26 51.6136972222 0.9046694444 +27 51.6126944444 0.9015722222 +28 51.61373333329999 0.8996138888999999 +29 51.6139333333 0.8951472221999999 +30 51.6150694444 0.8891527778 +31 51.6140055556 0.877525 +32 51.61255833330001 0.8742555556 +33 51.6098166667 0.87235 +34 51.6004694444 0.8720472222 +35 51.5966361111 0.87065 +36 51.5943666667 0.8677638889000001 +37 51.5918861111 0.8625527778 +38 51.5916111111 0.8590694444 +39 51.5919 0.8508555556 +40 51.5927583333 0.8451333333 +41 51.59278055560001 0.8405138889 +42 51.5947222222 0.8377777778000001 +43 51.58333333329999 0.8383333333 +44 51.5666666667 0.8333333333000001 +45 51.5380555556 0.8011111111 +46 51.50249999999999 0.8541666667 +47 51.5 0.8833333333 +48 51.6205555556 1.2008333333 +49 51.6205555556 0.9266666667 +50 51.83333333329999 0.9161111111 +51 51.8108333333 0.9144444443999998 +52 51.8091666667 0.98 +53 51.8316666667 0.9811111111000002 +54 51.83333333329999 0.9161111111 +55 51.53661111109999 -0.1529333333 +56 51.53789408709999 -0.1549267573 +57 51.5389111961 -0.1572818369 +58 51.5396236997 -0.1599088899 +59 51.5400044583 -0.1627078613 +60 51.5400389683 -0.1655721364 +61 51.5397259152 -0.1683926087 +62 51.5390772237 -0.1710618431 +63 51.53811760280001 -0.1734781752 +64 51.5368836029 -0.1755495885 +65 51.5354222222 -0.1771972222 +66 51.5076638889 -0.2023722222 +67 51.5060699613 -0.2035115549 +68 51.5043699176 -0.2041447262 +69 51.5026257804 -0.2042494731 +70 51.5009009245 -0.2038220493 +71 51.4992580171 -0.2028780428 +72 51.4977567415 -0.2014518003 +73 51.4964516304 -0.1995951734 +74 51.4953900866 -0.1973756297 +75 51.4946106635 -0.1948738011 +76 51.4941416667 -0.1921805556 +77 51.4890388889 -0.1464694444 +78 51.48287500000001 -0.1468722222 +79 51.4811955082 -0.1467340709 +80 51.4795600798 -0.1461068208 +81 51.4780238809 -0.1450111174 +82 51.4766387391 -0.1434839716 +83 51.4754513811 -0.141576937 +84 51.47450185809999 -0.1393543671 +85 51.47382219699999 -0.1368912443 +86 51.4734353207 -0.1342706517 +87 51.4733542773 -0.1315809745 +88 51.4735818 -0.1289129236 +89 51.4741102153 -0.1263564821 +90 51.4749217016 -0.1239978753 +91 51.4759888889 -0.1219166667 +92 51.48111111110001 -0.1136111111 +93 51.482252708 -0.1120090522 +94 51.483560414 -0.1107683543 +95 51.4849782611 -0.109891236 +96 51.4864671731 -0.1094019057 +97 51.4879861111 -0.1093138889 +98 51.5003194444 -0.1102416667 +99 51.5017362939 -0.1105268172 +100 51.50310830229999 -0.1111609871 +101 51.50440206899999 -0.1121293381 +102 51.5055861111 -0.1134083333 +103 51.53661111109999 -0.1529333333 +104 51.52371388890001 -0.09652500000000001 +105 51.5188833333 -0.1147444444 +106 51.5102972222 -0.1176944444 +107 51.5044888889 -0.0757138889 +108 51.51206666669999 -0.0716472222 +109 51.5216055556 -0.0775861111 +110 51.52371388890001 -0.09652500000000001 +111 51.5097055556 -0.0068583333 +112 51.5111814939 -0.0082867913 +113 51.5123684169 -0.0103077723 +114 51.51329883229999 -0.0126486151 +115 51.5139399674 -0.0152268831 +116 51.51426923799999 -0.0179517632 +117 51.51427504499999 -0.020727269 +118 51.5139571838 -0.0234556276 +119 51.5133268516 -0.0260407298 +120 51.51240625220001 -0.0283915214 +121 51.5112278124 -0.030425215 +122 51.5098330386 -0.0320702078 +123 51.50827105250001 -0.0332686036 +124 51.5065968595 -0.0339782479 +125 51.5048694103 -0.0341742076 +126 51.5031495242 -0.0338496416 +127 51.5014977474 -0.033016033 +128 51.4999722222 -0.0317027778 +129 51.48911111110001 -0.0202666667 +130 51.4881604117 -0.0187899397 +131 51.4874451822 -0.0170196811 +132 51.4870446916 -0.0150110296 +133 51.4869869497 -0.0129044713 +134 51.4872759947 -0.0108473335 +135 51.4878916114 -0.0089834902 +136 51.4887907435 -0.0074433086 +137 51.4899105027 -0.0063345359 +138 51.4911725642 -0.005734762 +139 51.49248864270001 -0.005685986 +140 51.4937666667 -0.0061916667 +141 51.49840277780001 -0.0092722222 +142 51.5097055556 -0.0068583333 +143 51.37758888890001 -0.4969416667 +144 51.3693692222 -0.5178943056 +145 51.3669779903 -0.5149878589 +146 51.3644324142 -0.5124379479 +147 51.36175325 -0.5102653056 +148 51.369975 -0.4893055556 +149 51.37758888890001 -0.4969416667 +150 51.6217164382 -0.5129944444 +151 51.62153986119999 -0.5184936191 +152 51.621012006 -0.5239343742 +153 51.6201384801 -0.5292589149 +154 51.6189285623 -0.5344106889 +155 51.6173951042 -0.5393349903 +156 51.6155543924 -0.5439795438 +157 51.6134259744 -0.5482950621 +158 51.6110324506 -0.5522357706 +159 51.608399232 -0.5557598936 +160 51.60555427029999 -0.5588300976 +161 51.60252775930001 -0.5614138859 +162 51.5993518132 -0.5634839411 +163 51.59606012529999 -0.5650184115 +164 51.5926876095 -0.5660011389 +165 51.589270029 -0.5664218254 +166 51.585843617 -0.5662761375 +167 51.5824446922 -0.5655657464 +168 51.57910927410001 -0.5642983057 +169 51.57587270119999 -0.5624873639 +170 51.5727692576 -0.5601522173 +171 51.5698318103 -0.5573177001 +172 51.5670914623 -0.5540139185 +173 51.56457722420001 -0.5502759287 +174 51.56231570839999 -0.5461433639 +175 51.56033084849999 -0.5416600139 +176 51.55864364759999 -0.5368733613 +177 51.5572719567 -0.5318340803 +178 51.5562302872 -0.5265955023 +179 51.5555296584 -0.5212130539 +180 51.5551774815 -0.5157436739 +181 51.5551774815 -0.510245215 +182 51.5555296584 -0.504775835 +183 51.5562302872 -0.4993933866 +184 51.5572719567 -0.4941548086 +185 51.55864364759999 -0.4891155276 +186 51.56033084849999 -0.484328875 +187 51.56231570839999 -0.4798455249 +188 51.56457722420001 -0.4757129602 +189 51.5670914623 -0.4719749703 +190 51.5698318103 -0.4686711888000001 +191 51.5727692576 -0.4658366715999999 +192 51.57587270119999 -0.4635015249 +193 51.57910927410001 -0.4616905832 +194 51.5824446922 -0.4604231424 +195 51.585843617 -0.4597127514 +196 51.589270029 -0.4595670635 +197 51.5926876095 -0.4599877499 +198 51.59606012529999 -0.4609704774 +199 51.5993518132 -0.4625049477 +200 51.60252775930001 -0.464575003 +201 51.60555427029999 -0.4671587913 +202 51.608399232 -0.4702289953 +203 51.6110324506 -0.4737531183000001 +204 51.6134259744 -0.4776938267 +205 51.6155543924 -0.4820093451 +206 51.6173951042 -0.4866538986 +207 51.6189285623 -0.4915782 +208 51.6201384801 -0.4967299739 +209 51.621012006 -0.5020545147 +210 51.62153986119999 -0.5074952698 +211 51.6217164382 -0.5129944444 +212 51.5599277778 -0.5756055556 +213 51.56767425 -0.5547771667 +214 51.57010516770001 -0.5576101111 +215 51.5726852958 -0.5600801312 +216 51.5753936389 -0.5621670833 +217 51.56765 -0.5829861111 +218 51.5599277778 -0.5756055556 +219 51.6166444444 -0.450975 +220 51.60916325 -0.4711767778000001 +221 51.6067302115 -0.4683454518999999 +222 51.6041480831 -0.4658782366 +223 51.6014379167 -0.4637951944 +224 51.6089222222 -0.4435833333 +225 51.6166444444 -0.450975 +226 51.6064472222 -0.5820527778 +227 51.6001324167 -0.5630313056 +228 51.6028946338 -0.5611342148 +229 51.6055390603 -0.5588447291 +230 51.6080441389 -0.5561814444 +231 51.61437500000001 -0.57525 +232 51.6064472222 -0.5820527778 +233 51.57097499999999 -0.4448222222000001 +234 51.57697613890001 -0.4628163333 +235 51.5742051095 -0.464678404 +236 51.5715499091 -0.4669335187 +237 51.5690321389 -0.4695632778 +238 51.5630472222 -0.4516166667 +239 51.57097499999999 -0.4448222222000001 +240 51.519198392 -0.46135 +241 51.5190207088 -0.4675046258 +242 51.5184891791 -0.4736065998 +243 51.51760834980001 -0.4796037246 +244 51.5163857558 -0.4854447065999999 +245 51.5148318544 -0.4910795983 +246 51.51295993590001 -0.4964602286 +247 51.5107860084 -0.5015406165 +248 51.50832866060001 -0.5062773666 +249 51.5056089011 -0.5106300405 +250 51.5026499783 -0.5145615031 +251 51.49947718029999 -0.5180382389 +252 51.4961176176 -0.5210306378 +253 51.4925999902 -0.5235132452 +254 51.4889543421 -0.525464977 +255 51.4852118033 -0.526869296 +256 51.48140432329999 -0.5277143491 +257 51.47756439840001 -0.5279930642 +258 51.4737247933 -0.5277032056 +259 51.4699182621 -0.5268473884 +260 51.46617726860001 -0.5254330514 +261 51.46253370969999 -0.5234723888 +262 51.4590186443 -0.5209822419 +263 51.4556620291 -0.5179839515 +264 51.4524924637 -0.5145031729 +265 51.4495369488 -0.510569654 +266 51.4468206561 -0.5062169801 +267 51.4443667159 -0.5014822864 +268 51.4421960211 -0.4964059411 +269 51.4403270501 -0.4910312023 +270 51.4387757108 -0.4854038501 +271 51.4375552059 -0.479571799 +272 51.436675922 -0.4735846922 +273 51.436145341 -0.4674934822 +274 51.43596797760001 -0.46135 +275 51.436145341 -0.4552065178 +276 51.436675922 -0.4491153078 +277 51.4375552059 -0.443128201 +278 51.4387757108 -0.4372961499 +279 51.4403270501 -0.4316687977 +280 51.4421960211 -0.4262940589 +281 51.4443667159 -0.4212177136 +282 51.4468206561 -0.4164830199 +283 51.4495369488 -0.412130346 +284 51.4524924637 -0.4081968271 +285 51.4556620291 -0.4047160485 +286 51.4590186443 -0.4017177581 +287 51.46253370969999 -0.3992276111999999 +288 51.46617726860001 -0.3972669486000001 +289 51.4699182621 -0.3958526116 +290 51.4737247933 -0.3949967944000001 +291 51.47756439840001 -0.3947069358 +292 51.48140432329999 -0.3949856508999999 +293 51.4852118033 -0.395830704 +294 51.4889543421 -0.3972350230000001 +295 51.4925999902 -0.3991867548 +296 51.4961176176 -0.4016693622 +297 51.49947718029999 -0.4046617611 +298 51.5026499783 -0.4081384969 +299 51.5056089011 -0.4120699595000001 +300 51.50832866060001 -0.4164226334 +301 51.5107860084 -0.4211593835 +302 51.51295993590001 -0.4262397714 +303 51.5148318544 -0.4316204017 +304 51.5163857558 -0.4372552934000001 +305 51.51760834980001 -0.4430962754 +306 51.5184891791 -0.4490934002 +307 51.5190207088 -0.4551953742000001 +308 51.519198392 -0.46135 +309 51.4704933333 -0.5569003333 +310 51.4706154722 -0.5270472778 +311 51.473972328 -0.5277391047 +312 51.4773531895 -0.5279918993 +313 51.4807356961 -0.527803899 +314 51.48409747220001 -0.52717625 +315 51.48397538890001 -0.5570173333 +316 51.4704933333 -0.5569003333 +317 51.4846374722 -0.3613735833 +318 51.4845450833 -0.3956410556000001 +319 51.4811877781 -0.3949547368 +320 51.4778067502 -0.3947077047 +321 51.47442436730001 -0.3949014835999999 +322 51.471063 -0.3955346944 +323 51.47115541669999 -0.3612565833 +324 51.4846374722 -0.3613735833 +325 51.45779225 -0.5542044167 +326 51.4579273056 -0.5200781389 +327 51.46113478249999 -0.5225554954 +328 51.4644627941 -0.5245850906 +329 51.4678869878 -0.5261519863 +330 51.4713823056 -0.5272446111 +331 51.47127436110001 -0.5543178889 +332 51.45779225 -0.5542044167 +333 51.4719051944 -0.3622085 +334 51.4718188333 -0.3953535278 +335 51.4683164757 -0.3963867682 +336 51.46488210049999 -0.397895493 +337 51.4615408393 -0.3998685359 +338 51.4583171389 -0.4022913611 +339 51.4584231111 -0.3620950278 +340 51.4719051944 -0.3622085 +341 51.5860694194 -0.4197222222 +342 51.58589284140001 -0.4252170924999999 +343 51.5853649835 -0.4306535891 +344 51.58449145300001 -0.4359739627 +345 51.5832815289 -0.4411217051 +346 51.5817480627 -0.4460421536 +347 51.5799073411 -0.4506830738000001 +348 51.5777789117 -0.4549952171 +349 51.5753853748 -0.4589328445 +350 51.5727521418 -0.4624542133000001 +351 51.56990716420001 -0.4655220189 +352 51.5668806359 -0.4681037901 +353 51.5637046715 -0.4701722306 +354 51.56041296439999 -0.4717055057 +355 51.5570404286 -0.4726874696 +356 51.5536228274 -0.4731078322 +357 51.5501963944 -0.4729622633 +358 51.5467974485 -0.4722524326 +359 51.54346200929999 -0.4709859873 +360 51.5402254156 -0.4691764654 +361 51.53712195180001 -0.4668431476 +362 51.53418448519999 -0.4640108489 +363 51.5314441189 -0.4607096516 +364 51.5289298638 -0.4569745846 +365 51.5266683326 -0.45284525 +366 51.5246834591 -0.4483654033 +367 51.5229962465 -0.4435824903 +368 51.521624546 -0.4385471456000001 +369 51.5205828693 -0.4333126589 +370 51.51988223559999 -0.4279344138 +371 51.5195300562 -0.4224693049 +372 51.5195300562 -0.4169751395 +373 51.51988223559999 -0.4115100306 +374 51.5205828693 -0.4061317855 +375 51.521624546 -0.4008972988 +376 51.5229962465 -0.3958619541 +377 51.5246834591 -0.3910790411 +378 51.5266683326 -0.3865991945000001 +379 51.5289298638 -0.3824698599 +380 51.5314441189 -0.3787347928 +381 51.53418448519999 -0.3754335956 +382 51.53712195180001 -0.3726012968 +383 51.5402254156 -0.3702679791 +384 51.54346200929999 -0.3684584571999999 +385 51.5467974485 -0.3671920117999999 +386 51.5501963944 -0.3664821812 +387 51.5536228274 -0.3663366122 +388 51.5570404286 -0.3667569749 +389 51.56041296439999 -0.3677389388 +390 51.5637046715 -0.3692722138 +391 51.5668806359 -0.3713406543 +392 51.56990716420001 -0.3739224255 +393 51.5727521418 -0.3769902312 +394 51.5753853748 -0.3805115998999999 +395 51.5777789117 -0.3844492274 +396 51.5799073411 -0.3887613706 +397 51.5817480627 -0.3934022908 +398 51.5832815289 -0.3983227393 +399 51.58449145300001 -0.4034704818 +400 51.5853649835 -0.4087908553 +401 51.58589284140001 -0.414227352 +402 51.5860694194 -0.4197222222 +403 51.5306527778 -0.4949055556 +404 51.53710075 -0.466825 +405 51.5398120238 -0.4689011239999999 +406 51.54262895259999 -0.4705770388 +407 51.5455286111 -0.4718390278 +408 51.5390916667 -0.4998722221999999 +409 51.5306527778 -0.4949055556 +410 51.5750055556 -0.3429888889 +411 51.5682804444 -0.3724551111 +412 51.5655610198 -0.3704066466 +413 51.5627375531 -0.3687601003 +414 51.55983305560001 -0.3675288056 +415 51.5665694444 -0.3380138889 +416 51.5750055556 -0.3429888889 +417 51.68911605390001 -0.32585 +418 51.68893947859999 -0.3313573375 +419 51.68841162860001 -0.3368061684 +420 51.6875381112 -0.3421386119 +421 51.6863282054 -0.3472980312 +422 51.68479476259999 -0.3522296393 +423 51.6829540693 -0.3568810829999999 +424 51.680825673 -0.3612030018 +425 51.6784321737 -0.365149553 +426 51.67579898259999 -0.3686788992 +427 51.672954051 -0.3717536515000001 +428 51.6699275723 -0.3743412651 +429 51.66675166080001 -0.3764143825 +430 51.66346000930001 -0.3779511197 +431 51.6600875314 -0.378935295 +432 51.6566699898 -0.3793565956 +433 51.65324361759999 -0.3792106819 +434 51.6498447329 -0.3784992283 +435 51.6465093546 -0.3772298997 +436 51.64327282090001 -0.3754162653999999 +437 51.64016941549999 -0.3730776505000001 +438 51.6372320048 -0.3702389262 +439 51.6344916913 -0.3669302437 +440 51.6319774852 -0.3631867112000001 +441 51.62971599849999 -0.3590480206 +442 51.62773116449999 -0.3545580267 +443 51.62604398559999 -0.3497642823 +444 51.6246723128 -0.3447175366 +445 51.62363065710001 -0.3394711997 +446 51.6229300376 -0.3340807801 +447 51.62257786529999 -0.3286033007 +448 51.62257786529999 -0.3230966993 +449 51.6229300376 -0.3176192199 +450 51.62363065710001 -0.3122288003 +451 51.6246723128 -0.3069824634 +452 51.62604398559999 -0.3019357177 +453 51.62773116449999 -0.2971419733 +454 51.62971599849999 -0.2926519794 +455 51.6319774852 -0.2885132888 +456 51.6344916913 -0.2847697563 +457 51.6372320048 -0.2814610738 +458 51.64016941549999 -0.2786223495 +459 51.64327282090001 -0.2762837346 +460 51.6465093546 -0.2744701003 +461 51.6498447329 -0.2732007717 +462 51.65324361759999 -0.2724893181 +463 51.6566699898 -0.2723434044 +464 51.6600875314 -0.272764705 +465 51.66346000930001 -0.2737488803 +466 51.66675166080001 -0.2752856175 +467 51.6699275723 -0.2773587349 +468 51.672954051 -0.2799463485 +469 51.67579898259999 -0.2830211008 +470 51.6784321737 -0.286550447 +471 51.680825673 -0.2904969982 +472 51.6829540693 -0.294818917 +473 51.68479476259999 -0.2994703607 +474 51.6863282054 -0.3044019688 +475 51.6875381112 -0.3095613881 +476 51.68841162860001 -0.3148938316 +477 51.68893947859999 -0.3203426625 +478 51.68911605390001 -0.32585 +479 51.6427944444 -0.40025 +480 51.6454770833 -0.3767162778 +481 51.64837118879999 -0.3780102409 +482 51.6513260665 -0.3788797193999999 +483 51.6543176667 -0.3793175556 +484 51.6516361111 -0.4028416667 +485 51.6427944444 -0.40025 +486 51.66880833330001 -0.251425 +487 51.6661527222 -0.2749615278 +488 51.6632575555 -0.2736733649 +489 51.6603019573 -0.2728102231 +490 51.65731000000001 -0.2723790556 +491 51.65996666670001 -0.2488333333 +492 51.66880833330001 -0.251425 +493 51.5385224685 0.0551777778 +494 51.5383458893 0.049688635 +495 51.5378180277 0.04425780480000001 +496 51.5369444912 0.0389429762 +497 51.53573455860001 0.0338005981 +498 51.5342010816 0.0288852764 +499 51.5323603469 0.0242491907 +500 51.53023190230001 0.0199415384 +501 51.527838348 0.0160080105 +502 51.5252050956 0.0124903067 +503 51.5223600968 0.0094256923 +504 51.5193335456 0.0068466052 +505 51.5161575568 0.0047803132 +506 51.512865824 0.0032486287 +507 51.5094932614 0.0022676808 +508 51.5060756327 0.001847749 +509 51.50264917169999 0.0019931596 +510 51.4992501975 0.0027022447 +511 51.4959147301 0.0039673655 +512 51.49267810879999 0.005774998199999999 +513 51.489574618 0.0081058824 +514 51.48663712559999 0.0109352292 +515 51.4838967349 0.0142329877 +516 51.4813824572 0.0179641657 +517 51.4791209055 0.0220892021 +518 51.4771360138 0.0265643871 +519 51.47544878560001 0.0313423241 +520 51.4740770724 0.0363724312 +521 51.473035386 0.0416014737 +522 51.4723347457 0.0469741258 +523 51.471982563 0.05243355169999999 +524 51.471982563 0.0579220039 +525 51.4723347457 0.0633814298 +526 51.473035386 0.0687540818 +527 51.4740770724 0.0739831244 +528 51.47544878560001 0.0790132314 +529 51.4771360138 0.0837911685 +530 51.4791209055 0.0882663534 +531 51.4813824572 0.0923913899 +532 51.4838967349 0.0961225678 +533 51.48663712559999 0.0994203263 +534 51.489574618 0.1022496732 +535 51.49267810879999 0.1045805574 +536 51.4959147301 0.1063881901 +537 51.4992501975 0.1076533108 +538 51.50264917169999 0.1083623959 +539 51.5060756327 0.1085078065 +540 51.5094932614 0.1080878748 +541 51.512865824 0.1071069268 +542 51.5161575568 0.1055752423 +543 51.5193335456 0.1035089504 +544 51.5223600968 0.1009298632 +545 51.5252050956 0.0978652489 +546 51.527838348 0.094347545 +547 51.53023190230001 0.0904140172 +548 51.5323603469 0.0861063648 +549 51.5342010816 0.0814702792 +550 51.53573455860001 0.0765549574 +551 51.5369444912 0.0714125794 +552 51.5378180277 0.0660977508 +553 51.5383458893 0.06066692059999999 +554 51.5385224685 0.0551777778 +555 51.50327555559999 -0.0265288333 +556 51.5023953889 0.0020265 +557 51.50539711759999 0.0018316307 +558 51.5083975865 0.0020711489 +559 51.5113723611 0.0027431944 +560 51.5122523333 -0.0258050833 +561 51.50327555559999 -0.0265288333 +562 51.5071330556 0.1372346667 +563 51.5080571389 0.1083335278 +564 51.5050552868 0.1085236627 +565 51.5020549588 0.1082794163 +566 51.4990805833 0.1076028611 +567 51.49815627780001 0.136511 +568 51.5071330556 0.1372346667 +569 51.6857966284 0.1560083333 +570 51.685620053 0.1505013986 +571 51.68509220280001 0.1450529662 +572 51.684218685 0.1397209126 +573 51.68300877859999 0.1345618705 +574 51.681475335 0.129630623 +575 51.6796346408 0.1249795192 +576 51.67750624340001 0.1206579162 +577 51.6751127429 0.1167116533 +578 51.67247955050001 0.1131825649 +579 51.6696346173 0.110108037 +580 51.66660813710001 0.1075206121 +581 51.66343222390001 0.1054476458 +582 51.6601405706 0.1039110205 +583 51.6567680908 0.1029269166 +584 51.6533505473 0.1025056463 +585 51.6499241731 0.1026515488 +586 51.6465252864 0.1033629501 +587 51.6431899062 0.1046321855 +588 51.6399533706 0.1064456869 +589 51.6368499633 0.1087841307 +590 51.63391255079999 0.1116226474 +591 51.6311722356 0.1149310881 +592 51.6286580279 0.1186743472 +593 51.6263965398 0.1228127354 +594 51.62441170450001 0.1273024016 +595 51.6227245245 0.132095796 +596 51.6213528508 0.1371421734 +597 51.6203111944 0.1423881274 +598 51.61961057449999 0.1477781538 +599 51.61925840200001 0.1532552335 +600 51.61925840200001 0.1587614331 +601 51.61961057449999 0.1642385129 +602 51.6203111944 0.1696285392 +603 51.6213528508 0.1748744933 +604 51.6227245245 0.1799208706 +605 51.62441170450001 0.1847142651 +606 51.6263965398 0.1892039312 +607 51.6286580279 0.1933423195 +608 51.6311722356 0.1970855786 +609 51.63391255079999 0.2003940193 +610 51.6368499633 0.2032325359 +611 51.6399533706 0.2055709798 +612 51.6431899062 0.2073844812 +613 51.6465252864 0.2086537166 +614 51.6499241731 0.2093651178 +615 51.6533505473 0.2095110204 +616 51.6567680908 0.2090897501 +617 51.6601405706 0.2081056462 +618 51.66343222390001 0.2065690208 +619 51.66660813710001 0.2044960546 +620 51.6696346173 0.2019086297 +621 51.67247955050001 0.1988341018 +622 51.6751127429 0.1953050134 +623 51.67750624340001 0.1913587504 +624 51.6796346408 0.1870371475 +625 51.681475335 0.1823860437 +626 51.68300877859999 0.1774547962 +627 51.684218685 0.172295754 +628 51.68509220280001 0.1669637005 +629 51.685620053 0.161515268 +630 51.6857966284 0.1560083333 +631 51.6095305556 0.114975 +632 51.62320063889999 0.1306218889 +633 51.6247434871 0.1264803317 +634 51.62651232070001 0.1225788083 +635 51.62849275 0.1189490556 +636 51.61475 0.1032222222 +637 51.6095305556 0.114975 +638 51.6945361111 0.1946944444 +639 51.6821273889 0.1804416944 +640 51.6806366835 0.1846372067 +641 51.6789167892 0.1885991606 +642 51.67698175 0.1922952778 +643 51.6893194444 0.2064694444 +644 51.6945361111 0.1946944444 +645 51.6093166667 0.1154222222 +646 51.62303599999999 0.1311190278 +647 51.6245517675 0.126951311 +648 51.6262951166 0.1230198351 +649 51.6282518611 0.1193565833 +650 51.61453611109999 0.1036666667 +651 51.6093166667 0.1154222222 +652 51.6943527778 0.1951388889 +653 51.68197180559999 0.1809234167 +654 51.6804547511 0.1850942614 +655 51.678710016 0.1890278444 +656 51.67675183330001 0.1926921111 +657 51.6891361111 0.2069138889 +658 51.6943527778 0.1951388889 +659 51.9266121564 0.235 +660 51.92643448310001 0.2287898076 +661 51.92590298339999 0.2226327443 +662 51.9250222041 0.2165814812 +663 51.9237996799 0.2106877765 +664 51.9222458679 0.2050020304 +665 51.92037405800001 0.1995728501 +666 51.9182002582 0.1944466326 +667 51.9157430564 0.1896671656 +668 51.9130234609 0.1852752525 +669 51.9100647192 0.1813083633 +670 51.90689211849999 0.1778003149 +671 51.9035327683 0.1747809834 +672 51.9000153673 0.1722760514 +673 51.896369958 0.1703067912 +674 51.8926276688 0.1688898867 +675 51.8888204475 0.1680372953 +676 51.8849807881 0.1677561503 +677 51.8811414532 0.1680487046 +678 51.87733519460001 0.1689123167 +679 51.8735944735 0.1703394781 +680 51.8699511843 0.1723178822 +681 51.8664363832 0.1748305335 +682 51.86308002400001 0.1778558969 +683 51.8599107037 0.1813680845 +684 51.85695542020001 0.1853370792 +685 51.8542393427 0.1897289923 +686 51.851785599 0.1945063538 +687 51.8496150796 0.1996284322 +688 51.84774626079999 0.2050515805 +689 51.84619504860001 0.2107296074 +690 51.8449746444 0.2166141682 +691 51.8440954332 0.2226551744 +692 51.8435648963 0.2288012169 +693 51.8433875477 0.235 +694 51.8435648963 0.2411987831 +695 51.8440954332 0.2473448256 +696 51.8449746444 0.2533858318 +697 51.84619504860001 0.2592703926 +698 51.84774626079999 0.2649484195 +699 51.8496150796 0.2703715678 +700 51.851785599 0.2754936462 +701 51.8542393427 0.2802710077 +702 51.85695542020001 0.2846629208 +703 51.8599107037 0.2886319155 +704 51.86308002400001 0.2921441031 +705 51.8664363832 0.2951694665 +706 51.8699511843 0.2976821178 +707 51.8735944735 0.2996605219 +708 51.87733519460001 0.3010876833 +709 51.8811414532 0.3019512954 +710 51.8849807881 0.3022438497 +711 51.8888204475 0.3019627047 +712 51.8926276688 0.3011101133 +713 51.896369958 0.2996932088 +714 51.9000153673 0.2977239486 +715 51.9035327683 0.2952190166 +716 51.90689211849999 0.2921996851 +717 51.9100647192 0.2886916367 +718 51.9130234609 0.2847247475 +719 51.9157430564 0.2803328344 +720 51.9182002582 0.2755533674 +721 51.92037405800001 0.2704271499 +722 51.9222458679 0.2649979696 +723 51.9237996799 0.2593122235 +724 51.9250222041 0.2534185188 +725 51.92590298339999 0.2473672557 +726 51.92643448310001 0.2412101924 +727 51.9266121564 0.235 +728 51.8410361111 0.1788194444 +729 51.85167430559999 0.1947456944 +730 51.8535562167 0.1909710506 +731 51.8556015888 0.187424914 +732 51.85779980560001 0.1841257222 +733 51.84715277780001 0.1681888889 +734 51.8410361111 0.1788194444 +735 51.93113055560001 0.2941833333 +736 51.9184224444 0.2750736667 +737 51.916548197 0.2788639154 +738 51.9145097839 0.2824255347 +739 51.91231783329999 0.28574 +740 51.9250166667 0.3048388889 +741 51.93113055560001 0.2941833333 +742 51.9282896919 0.4491666667 +743 51.9281131227 0.4436301033 +744 51.927585291 0.4381523581 +745 51.926711804 0.4327916200999999 +746 51.9255019406 0.4276048275 +747 51.9239685519 0.422647059 +748 51.92212792399999 0.4179709460000001 +749 51.9199996043 0.4136261113 +750 51.91760619210001 0.4096586409 +751 51.9149730981 0.4061105941 +752 51.9121282729 0.4030195576 +753 51.90910190909999 0.4004182481 +754 51.90592612 0.3983341674 +755 51.9026345974 0.3967893144 +756 51.8992622536 0.3957999552 +757 51.89584485030001 0.3953764561 +758 51.8924186188 0.3955231779999999 +759 51.88901987600001 0.3962384364 +760 51.88568463899999 0.3975145241 +761 51.8824482445 0.3993377987 +762 51.8793449744 0.4016888316 +763 51.8764076934 0.4045426185 +764 51.8736675024 0.4078688481 +765 51.87115341000001 0.4116322255 +766 51.86889202660001 0.4157928483000001 +767 51.86690728399999 0.4203066295 +768 51.86522018340001 0.4251257647 +769 51.86384857459999 0.4301992364 +770 51.86280696779999 0.4354733526 +771 51.8621063813 0.4408923116999999 +772 51.8617542257 0.4463987897999999 +773 51.8617542257 0.4519345435 +774 51.8621063813 0.4574410216 +775 51.86280696779999 0.4628599807 +776 51.86384857459999 0.4681340969 +777 51.86522018340001 0.4732075687 +778 51.86690728399999 0.4780267038 +779 51.86889202660001 0.4825404851000001 +780 51.87115341000001 0.4867011077999999 +781 51.8736675024 0.4904644852 +782 51.8764076934 0.4937907147999999 +783 51.8793449744 0.4966445018 +784 51.8824482445 0.4989955347 +785 51.88568463899999 0.5008188092 +786 51.88901987600001 0.502094897 +787 51.8924186188 0.5028101553 +788 51.89584485030001 0.5029568773 +789 51.8992622536 0.5025333781 +790 51.9026345974 0.5015440189 +791 51.90592612 0.4999991659 +792 51.90910190909999 0.4979150853 +793 51.9121282729 0.4953137757 +794 51.9149730981 0.4922227392 +795 51.91760619210001 0.4886746924 +796 51.9199996043 0.484707222 +797 51.92212792399999 0.4803623874 +798 51.9239685519 0.4756862743 +799 51.9255019406 0.4707285057999999 +800 51.926711804 0.4655417132 +801 51.927585291 0.4601809752 +802 51.9281131227 0.45470323 +803 51.9282896919 0.4491666667 +804 51.8864027778 0.3730888889 +805 51.88766425 0.3966865556 +806 51.89062131390001 0.3958296993000001 +807 51.89361413149999 0.3954070986 +808 51.8966183333 0.3954222778 +809 51.8953583333 0.3718527778 +810 51.8864027778 0.3730888889 +811 51.9035638889 0.5269916667 +812 51.9022398056 0.5016900556 +813 51.89928078159999 0.5025295237 +814 51.89628698540001 0.502934256 +815 51.8932828056 0.5029010556 +816 51.89460833329999 0.5282305556 +817 51.9035638889 0.5269916667 +818 51.8861333333 0.3729722222 +819 51.8873999167 0.3967850555999999 +820 51.8903525916 0.3958892902 +821 51.89334320879999 0.3954272954 +822 51.8963474167 0.3954029167000001 +823 51.8950888889 0.3717416667 +824 51.8861333333 0.3729722222 +825 51.9032611111 0.5270416667 +826 51.90194663890001 0.50179325 +827 51.8989830515 0.502589532 +828 51.8959871214 0.5029506279 +829 51.89298324999999 0.5028736667 +830 51.8943055556 0.5282722222 +831 51.9032611111 0.5270416667 +832 51.9477340257 0.6825 +833 51.947557457 0.6769610427 +834 51.9470296268 0.6714809291 +835 51.9461561423 0.6661178735 +836 51.94494628230001 0.6609288387 +837 51.94341289800001 0.6559689273 +838 51.94157227549999 0.6512907936 +839 51.9394439619 0.6469440818 +840 51.9370505568 0.6429748979 +841 51.93441747070001 0.6394253193 +842 51.9315726541 0.636332949 +843 51.9285462996 0.6337305176 +844 51.9253705205 0.631645539 +845 51.9220790084 0.6301000212 +846 51.9187066755 0.6291102374 +847 51.9152892834 0.6286865582 +848 51.9118630633 0.6288333463 +849 51.908464332 0.6295489163 +850 51.90512910650001 0.6308255577 +851 51.9018927233 0.632649622 +852 51.8987894642 0.635001672 +853 51.8958521937 0.6378566928 +854 51.8931120127 0.6411843597 +855 51.8905979296 0.6449493626 +856 51.8883365545 0.6491117818 +857 51.8863518193 0.6536275115 +858 51.8846647251 0.6584487265 +859 51.8832931215 0.6635243874 +860 51.8822515187 0.668800779 +861 51.8815509349 0.6742220758 +862 51.8811987806 0.6797309292 +863 51.8811987806 0.6852690708 +864 51.8815509349 0.6907779242 +865 51.8822515187 0.696199221 +866 51.8832931215 0.7014756126 +867 51.8846647251 0.7065512735000001 +868 51.8863518193 0.7113724885 +869 51.8883365545 0.7158882182 +870 51.8905979296 0.7200506374 +871 51.8931120127 0.7238156403 +872 51.8958521937 0.7271433072 +873 51.8987894642 0.729998328 +874 51.9018927233 0.7323503780000001 +875 51.90512910650001 0.7341744422999998 +876 51.908464332 0.7354510837 +877 51.9118630633 0.7361666536999999 +878 51.9152892834 0.7363134417999999 +879 51.9187066755 0.7358897625999999 +880 51.9220790084 0.7348999788 +881 51.9253705205 0.733354461 +882 51.9285462996 0.7312694824 +883 51.9315726541 0.728667051 +884 51.93441747070001 0.7255746807 +885 51.9370505568 0.7220251021 +886 51.9394439619 0.7180559182000001 +887 51.94157227549999 0.7137092064 +888 51.94341289800001 0.7090310727 +889 51.94494628230001 0.7040711613 +890 51.9461561423 0.6988821265 +891 51.9470296268 0.6935190709 +892 51.947557457 0.6880389573 +893 51.9477340257 0.6825 +894 51.8858888889 0.6188194444 +895 51.89362883329999 0.6405008056 +896 51.8960555344 0.6376370069 +897 51.8986320512 0.6351382452 +898 51.90133741670001 0.6330249167 +899 51.8936777778 0.6115694444 +900 51.8858888889 0.6188194444 +901 51.94202500000001 0.7473027778 +902 51.9343375 0.7256713333 +903 51.9318493242 0.7283957123 +904 51.9292193892 0.7307458014 +905 51.92646913890001 0.7327025 +906 51.93423611109999 0.7545583333 +907 51.94202500000001 0.7473027778 +908 51.6118921753 0.6933333333 +909 51.6117144943 0.6871661804 +910 51.6111829714 0.6810517867 +911 51.6103021536 0.6750424567 +912 51.6090795755 0.6691895887 +913 51.6075256945 0.6635432321 +914 51.60565380079999 0.6581516565 +915 51.6034799024 0.6530609364 +916 51.6010225879 0.648314556 +917 51.5983028658 0.6439530358 +918 51.5953439844 0.6400135864 +919 51.5921712314 0.6365297913 +920 51.5888117171 0.6335313205 +921 51.5852941413 0.63104368 +922 51.5816485477 0.6290879964 +923 51.5779060657 0.62768084 +924 51.5740986447 0.6268340873 +925 51.5702587803 0.6265548244 +926 51.5664192368 0.6268452906 +927 51.5626127676 0.627702865 +928 51.5588718361 0.6291200932 +929 51.5552283386 0.6310847554 +930 51.5517133334 0.6335799758 +931 51.54835677650001 0.6365843696 +932 51.5451872669 0.6400722293 +933 51.5422318046 0.644013746 +934 51.53951556090001 0.6483752663 +935 51.5370616655 0.6531195793 +936 51.5348910106 0.6582062349 +937 51.5330220742 0.6635918876 +938 51.5314707638 0.6692306642 +939 51.5302502819 0.6750745535 +940 51.5293710145 0.6810738118 +941 51.5288404435 0.6871773836 +942 51.5286630835 0.6933333333 +943 51.5288404435 0.699489283 +944 51.5293710145 0.7055928549 +945 51.5302502819 0.7115921131 +946 51.5314707638 0.7174360023999999 +947 51.5330220742 0.7230747791000001 +948 51.5348910106 0.7284604317 +949 51.5370616655 0.7335470874 +950 51.53951556090001 0.7382914004 +951 51.5422318046 0.7426529206000001 +952 51.5451872669 0.7465944374000001 +953 51.54835677650001 0.7500822969999998 +954 51.5517133334 0.7530866907999999 +955 51.5552283386 0.7555819112 +956 51.5588718361 0.7575465735 +957 51.5626127676 0.7589638016 +958 51.5664192368 0.7598213761 +959 51.5702587803 0.7601118423 +960 51.5740986447 0.7598325793 +961 51.5779060657 0.7589858267 +962 51.5816485477 0.7575786702 +963 51.5852941413 0.7556229865999999 +964 51.5888117171 0.7531353462 +965 51.5921712314 0.7501368754 +966 51.5953439844 0.7466530802 +967 51.5983028658 0.7427136308999999 +968 51.6010225879 0.7383521107 +969 51.6034799024 0.7336057302 +970 51.60565380079999 0.7285150102 +971 51.6075256945 0.7231234345 +972 51.6090795755 0.7174770779 +973 51.6103021536 0.7116242099 +974 51.6111829714 0.7056148799 +975 51.6117144943 0.6995004863 +976 51.6118921753 0.6933333333 +977 51.53595555559999 0.6291166667 +978 51.54249894439999 0.6436260556 +979 51.544803412 0.6405434667 +980 51.5472403342 0.637734927 +981 51.5497970556 0.6352150556 +982 51.5432416667 0.6206805556 +983 51.53595555559999 0.6291166667 +984 51.6042944444 0.7563638889 +985 51.5982206389 0.7428335 +986 51.5959248333 0.7459369184 +987 51.5934956228 0.7487662855 +988 51.5909456667 0.7513069167 +989 51.5970083333 0.7648138889000001 +990 51.6042944444 0.7563638889 +991 51.50322266999999 -0.1795388889 +992 51.5030460899 -0.1850237897 +993 51.5025182256 -0.1904504231 +994 51.5016446845 -0.1957611449 +995 51.5004347457 -0.2008995498 +996 51.4989012607 -0.2058110744 +997 51.4970605163 -0.2104435795 +998 51.4949320603 -0.2147479056 +999 51.49253849309999 -0.2186783971 +1000 51.4899052263 -0.2221933866 +1001 51.4870602117 -0.2252556374 +1002 51.4840336435 -0.2278327366 +1003 51.48085763660001 -0.2298974372 +1004 51.47756588469999 -0.2314279437 +1005 51.4741933023 -0.2324081392 +1006 51.4707756531 -0.2328277518 +1007 51.46734917130001 -0.2326824584 +1008 51.46395017609999 -0.2319739255 +1009 51.4606146879 -0.2307097858 +1010 51.4573780459 -0.2289035523 +1011 51.4542745352 -0.2265744705 +1012 51.4513370235 -0.22374731 +1013 51.4485966148 -0.2204520984 +1014 51.4460823203 -0.2167238008 +1015 51.44382075330001 -0.2126019478 +1016 51.44183584809999 -0.2081302155 +1017 51.4401486084 -0.2033559639 +1018 51.4387768857 -0.1983297361 +1019 51.43773519200001 -0.1931047256 +1020 51.4370345469 -0.187736216 +1021 51.4366823617 -0.1822809993 +1022 51.4366823617 -0.1767967785 +1023 51.4370345469 -0.1713415617 +1024 51.43773519200001 -0.1659730521 +1025 51.4387768857 -0.1607480417 +1026 51.4401486084 -0.1557218139 +1027 51.44183584809999 -0.1509475623 +1028 51.44382075330001 -0.14647583 +1029 51.4460823203 -0.142353977 +1030 51.4485966148 -0.1386256794 +1031 51.4513370235 -0.1353304678 +1032 51.4542745352 -0.1325033072 +1033 51.4573780459 -0.1301742255 +1034 51.4606146879 -0.128367992 +1035 51.46395017609999 -0.1271038523 +1036 51.46734917130001 -0.1263953194 +1037 51.4707756531 -0.126250026 +1038 51.4741933023 -0.1266696386 +1039 51.47756588469999 -0.1276498341 +1040 51.48085763660001 -0.1291803406 +1041 51.4840336435 -0.1312450412 +1042 51.4870602117 -0.1338221404 +1043 51.4899052263 -0.1368843911 +1044 51.49253849309999 -0.1403993807 +1045 51.4949320603 -0.1443298721 +1046 51.4970605163 -0.1486341983 +1047 51.4989012607 -0.1532667033 +1048 51.5004347457 -0.158178228 +1049 51.5016446845 -0.1633166329 +1050 51.5025182256 -0.1686273547 +1051 51.5030460899 -0.1740539881 +1052 51.50322266999999 -0.1795388889 +1053 51.5032916667 0.0990305556 +1054 51.4976583333 0.0834944444 +1055 51.4909166667 0.0804333333 +1056 51.4882305556 0.0945611111 +1057 51.4915305556 0.097125 +1058 51.4949638889 0.1065527778 +1059 51.5032916667 0.0990305556 +1060 51.4562194444 -0.1273222222 +1061 51.4538527778 -0.132775 +1062 51.4481638889 -0.132025 +1063 51.4472388889 -0.1223611111 +1064 51.4488194444 -0.1186333333 +1065 51.4525472222 -0.1174055556 +1066 51.4551111111 -0.1195583333 +1067 51.4562194444 -0.1273222222 +1068 51.4362277778 -0.4930166667 +1069 51.4301416667 -0.4903944444 +1070 51.42807222220001 -0.4851722222 +1071 51.4289388889 -0.4792944444 +1072 51.43160277779999 -0.4755583333 +1073 51.4384027778 -0.4780916667 +1074 51.4362277778 -0.4930166667 +1075 51.74201111109999 0.4828416667 +1076 51.73457222220001 0.4758444444 +1077 51.73124444439999 0.4857611110999999 +1078 51.7308777778 0.4934583333 +1079 51.7330944444 0.4965583332999999 +1080 51.7377777778 0.4958222222 +1081 51.74201111109999 0.4828416667 +1082 51.4456916667 -0.4374555555999999 +1083 51.4440722222 -0.4445888889 +1084 51.4351611111 -0.4464194444 +1085 51.4329861111 -0.4298361111 +1086 51.4443638889 -0.4255777777999999 +1087 51.4456916667 -0.4374555555999999 +1088 51.54883611109999 -0.1238444444 +1089 51.5393944444 -0.1224222222 +1090 51.54205 -0.1066055556 +1091 51.5491972222 -0.1114833333 +1092 51.5494138889 -0.1164833333 +1093 51.54883611109999 -0.1238444444 +1094 51.4561361111 -0.1751111111 +1095 51.45391944440001 -0.1822138889 +1096 51.4496 -0.1864583333 +1097 51.4432166667 -0.1783527778 +1098 51.4481388889 -0.1683916667 +1099 51.4561361111 -0.1751111111 +1100 51.52105277780001 -0.2490222222 +1101 51.5157277778 -0.2482861111 +1102 51.51224999999999 -0.245725 +1103 51.513125 -0.2311805556 +1104 51.5218972222 -0.2334805556 +1105 51.52105277780001 -0.2490222222 +1106 52.1686382148 0.9554138889 +1107 52.16846054749999 0.9491700573 +1108 52.16792906549999 0.9429796438999999 +1109 52.1670483157 0.9368956062 +1110 52.1658258326 0.9309699841 +1111 52.1642720733 0.9252534515999999 +1112 52.1624003276 0.91979488 +1113 52.1602266031 0.9146409181999999 +1114 52.15776948760001 0.9098355913 +1115 52.155049989 0.9054199238000001 +1116 52.1520913543 0.9014315882 +1117 52.1489188703 0.8979045841 +1118 52.1455596457 0.8948689485 +1119 52.1420423786 0.8923505021 +1120 52.13839711069999 0.8903706309 +1121 52.1346549692 0.8889461079 +1122 52.130847901 0.8880889535 +1123 52.1270083989 0.887806338 +1124 52.1231692242 0.8881005247 +1125 52.1193631272 0.8889688560999999 +1126 52.1156225676 0.8904037816000001 +1127 52.1119794383 0.8923929263000001 +1128 52.1084647939 0.8949192016 +1129 52.1051085866 0.8979609547000001 +1130 52.1019394118 0.9014921567 +1131 52.0989842656 0.9054826276 +1132 52.0962683158 0.9098982951 +1133 52.09381468880001 0.9147014867 +1134 52.0916442735 0.9198512507 +1135 52.0897755451 0.9253037047 +1136 52.0882244085 0.9310124084 +1137 52.087004064 0.9369287568999999 +1138 52.0861248961 0.9430023922 +1139 52.0855943853 0.9491816283999999 +1140 52.0854170454 0.9554138889 +1141 52.0855943853 0.9616461494 +1142 52.0861248961 0.9678253855999999 +1143 52.087004064 0.9738990208 +1144 52.0882244085 0.9798153694 +1145 52.0897755451 0.9855240730999999 +1146 52.0916442735 0.9909765271 +1147 52.09381468880001 0.9961262910000002 +1148 52.0962683158 1.0009294826 +1149 52.0989842656 1.0053451502 +1150 52.1019394118 1.0093356211 +1151 52.1051085866 1.0128668231 +1152 52.1084647939 1.0159085762 +1153 52.1119794383 1.0184348515 +1154 52.1156225676 1.0204239962 +1155 52.1193631272 1.0218589216 +1156 52.1231692242 1.0227272531 +1157 52.1270083989 1.0230214398 +1158 52.130847901 1.0227388243 +1159 52.1346549692 1.0218816699 +1160 52.13839711069999 1.0204571469 +1161 52.1420423786 1.0184772757 +1162 52.1455596457 1.0159588292 +1163 52.1489188703 1.0129231937 +1164 52.1520913543 1.0093961896 +1165 52.155049989 1.005407854 +1166 52.15776948760001 1.0009921865 +1167 52.1602266031 0.9961868596 +1168 52.1624003276 0.9910328978 +1169 52.1642720733 0.9855743262 +1170 52.1658258326 0.9798577937 +1171 52.1670483157 0.9739321716 +1172 52.16792906549999 0.9678481339 +1173 52.16846054749999 0.9616577205 +1174 52.1686382148 0.9554138889 +1175 52.08708213889999 0.8945785833 +1176 52.09594825 0.9104756667 +1177 52.0980224587 0.9069544023 +1178 52.10024747229999 0.9036846797 +1179 52.10261175 0.9006835277999999 +1180 52.0937486944 0.8847938611 +1181 52.08708213889999 0.8945785833 +1182 52.16778141670001 1.0178328056 +1183 52.1581005278 1.0003954167 +1184 52.1560243877 1.0039183892 +1185 52.15379737890001 1.0071885817 +1186 52.1514311111 1.010189 +1187 52.1611149444 1.0276337778 +1188 52.16778141670001 1.0178328056 +1189 52.1464944444 0.5095194444 +1190 52.1393277778 0.5008166667 +1191 52.1304 0.5051555556 +1192 52.1337222222 0.5260694444 +1193 52.1459222222 0.5192861111 +1194 52.1464944444 0.5095194444 +1195 52.06553888890001 1.4600444444 +1196 52.0590805556 1.449675 +1197 52.0519277778 1.4574888889 +1198 52.0552388889 1.4692555556 +1199 52.05961666670001 1.4700805556 +1200 52.06553888890001 1.4600444444 +EOF diff --git a/PathPlanning/DynamicWindowApproach/convert_KML_to_TSP.py b/PathPlanning/DynamicWindowApproach/convert_KML_to_TSP.py new file mode 100644 index 0000000000..3b4c6d70f5 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/convert_KML_to_TSP.py @@ -0,0 +1,38 @@ +import xml.etree.ElementTree as ET + +def parse_kml(kml_file): + tree = ET.parse(kml_file) + root = tree.getroot() + namespace = {'kml': 'http://www.opengis.net/kml/2.2'} + coordinates = [] + + for placemark in root.findall('.//kml:Placemark', namespace): + coords = placemark.find('.//kml:coordinates', namespace).text.strip() + for coord in coords.split(): + lon, lat, _ = map(float, coord.split(',')) + coordinates.append((lat, lon)) + + return coordinates + +def convert_to_tsp(coordinates, tsp_file): + with open(tsp_file, 'w') as f: + f.write(f"NAME: example\n") + f.write(f"TYPE: TSP\n") + f.write(f"DIMENSION: {len(coordinates)}\n") + f.write(f"EDGE_WEIGHT_TYPE: EUC_2D\n") + f.write(f"NODE_COORD_SECTION\n") + + for i, (lat, lon) in enumerate(coordinates, start=1): + f.write(f"{i} {lat} {lon}\n") + + f.write(f"EOF\n") + +# Main execution +kml_file = '/home/dell/ALNS/Fences.kml' +tsp_file = '/home/dell/ALNS/Fences.tsp' + +coordinates = parse_kml(kml_file) +convert_to_tsp(coordinates, tsp_file) + +print(f"Converted {len(coordinates)} points from {kml_file} to {tsp_file}") + From 56261effee7dd21e7e37f505d437f94f96169d1c Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:21:54 +0100 Subject: [PATCH 26/33] Add files via upload --- .../DynamicWindowApproach/follow-1-copter.sh | 61 +++++++++++++++++++ 1 file changed, 61 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/follow-1-copter.sh diff --git a/PathPlanning/DynamicWindowApproach/follow-1-copter.sh b/PathPlanning/DynamicWindowApproach/follow-1-copter.sh new file mode 100644 index 0000000000..8de997bea1 --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/follow-1-copter.sh @@ -0,0 +1,61 @@ +#!/bin/bash + +# Kill all SITL binaries when exiting +trap "killall -9 arducopter" SIGINT SIGTERM EXIT + +ROOTDIR=$PWD +COPTER=$ROOTDIR/build/sitl/bin/arducopter + +GCS_IP="127.0.0.1" + +# Check if Platform is Native Linux, WSL or Cygwin +unameOut="$(uname -s)" +if [[ "$(expr substr $unameOut 1 5)" == "Linux" ]]; then + if grep -q Microsoft /proc/version; then + MCAST_IP_PORT="127.0.0.1:14550" + else + MCAST_IP_PORT="" + fi +elif [[ "$(expr substr $unameOut 1 6)" == "CYGWIN" ]]; then + MCAST_IP_PORT="0.0.0.0:14550" +fi + +BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools/autotest/default_params/airsim-quadX.parm" + +[ -x "$COPTER" ] || { + ./waf configure --board sitl + ./waf copter +} + +# Start up main copter +#$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14550 --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & +# Start up main copter +$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14550 --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & + +# Start additional copters +#$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14551 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + +# Set number of extra copters +NCOPTERS="1" + +for i in $(seq $NCOPTERS); do + echo "Starting copter $i" + mkdir -p copter$i + SYSID=$(expr $i + 1) + FOLL_SYSID=$(expr $SYSID - 1) + + # Create default parameter file for the follower + cat < copter$i/follow.parm +SYSID_THISMAV $SYSID +FOLL_ENABLE 1 +FOLL_OFS_X -5 +FOLL_OFS_TYPE 1 +FOLL_SYSID $FOLL_SYSID +FOLL_DIST_MAX 1000 +EOF + pushd copter$i + $COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14551 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + popd +done +wait + From f0e1f625c22c4dfaddce9fbca0b6299473997770 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:27:29 +0100 Subject: [PATCH 27/33] Update Readme file --- PathPlanning/DynamicWindowApproach/Readme file | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/Readme file b/PathPlanning/DynamicWindowApproach/Readme file index f96388fd99..1e462aaa3f 100644 --- a/PathPlanning/DynamicWindowApproach/Readme file +++ b/PathPlanning/DynamicWindowApproach/Readme file @@ -1,6 +1,9 @@ -~/ardupilot$ ./libraries/SITL/examples/Airsim/follow-1-copter.sh -mavproxy.py --master=udpin:127.0.0.1:14550 --console --out=udpout:127.0.0.1:14552 -./mavproxy_kml.py +1. Run the UNreal Engine by Blocks.uproject -~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 take0ff_arm.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 -~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 Unreal_Ardupilo_Drones_DWA.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 + +2. ~/ardupilot$ ./libraries/SITL/examples/Airsim/follow-1-copter.sh +3. mavproxy.py --master=udpin:127.0.0.1:14550 --console --out=udpout:127.0.0.1:14552 +4. ./mavproxy_kml.py + +5. ~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 take0ff_arm.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 +6. ~/PythonRobotics/PathPlanning/DynamicWindowApproach$ python3 Unreal_Ardupilo_Drones_DWA.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 From f0caf6d5e58ff62d85d977f9d96e53cb6c4e5928 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 19:57:14 +0100 Subject: [PATCH 28/33] Add files via upload --- .../Unreal_Ardupilo_Drones_DWA.py | 230 ++++++++++++++++++ 1 file changed, 230 insertions(+) create mode 100644 PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py diff --git a/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py new file mode 100644 index 0000000000..f09a99b21f --- /dev/null +++ b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py @@ -0,0 +1,230 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +from __future__ import print_function +import numpy as np +import math +import matplotlib.pyplot as plt +import matplotlib.animation as animation +import threading +import queue +import random +import argparse +from dronekit import connect, VehicleMode, LocationGlobalRelative +from pymavlink import mavutil # Needed for command message definitions +from dwa import dwa_control, motion, RobotType, plot_robot + +# Files for destinations and fences +DATA_FILE = '/home/dell/ALNS/Destinations.tsp' +FENCES_FILE = '/home/dell/ALNS/Fences.tsp' + +class RobotType: + circle = 1 + rectangle = 2 + +def read_positions(file_path): + """Reads positions from a TSP file format.""" + positions = [] + with open(file_path, 'r') as f: + reading_nodes = False + for line in f: + if "NODE_COORD_SECTION" in line: + reading_nodes = True + elif "EOF" in line: + break + elif reading_nodes: + _, x, y = line.split() + positions.append((float(x), float(y))) + return positions + +def read_fences(file_path, radius=0.003, num_points=20): + """Reads fence positions from a TSP file format and converts them to polygonal obstacles.""" + fences = [] + centers = [] + with open(file_path, 'r') as f: + reading_nodes = False + for line in f: + if "NODE_COORD_SECTION" in line: + reading_nodes = True + elif "EOF" in line: + break + elif reading_nodes: + _, x, y = line.split() + center_x, center_y = float(x), float(y) + centers.append((center_x, center_y)) + # Generate points around the fence center to form a polygon + for i in range(num_points): + angle = 2 * math.pi * i / num_points + px = center_x + radius * math.cos(angle) + py = center_y + radius * math.sin(angle) + fences.append([px, py]) + return fences, centers + +class Config: + def __init__(self, fences_file): + self.max_speed = 1.0 # [m/s] + self.min_speed = -0.5 # [m/s] + self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s] + self.max_accel = 0.2 # [m/ss] + self.max_delta_yaw_rate = 40.0 * math.pi / 180.0 # [rad/ss] + self.v_resolution = 0.01 # [m/s] + self.yaw_rate_resolution = 0.1 * math.pi / 180.0 # [rad/s] + self.dt = 0.1 # [s] Time tick for motion prediction + self.predict_time = 3.0 # [s] + self.to_goal_cost_gain = 0.15 + self.speed_cost_gain = 1.0 + self.obstacle_cost_gain = 1.0 + self.robot_stuck_flag_cons = 0.001 # constant to prevent robot stucked + self.robot_type = RobotType.circle + self.robot_radius = 1.0 # [m] for collision check + self.robot_width = 0.5 # [m] for collision check + self.robot_length = 1.2 # [m] for collision check + + # Read the obstacles from the fences file + self.ob, self.centers = read_fences(fences_file) + +def get_location_offset(location, dNorth, dEast): + earth_radius = 6378137.0 # Radius of "spherical" earth + dLat = dNorth / earth_radius + dLon = dEast / (earth_radius * math.cos(math.pi * location.lat / 180)) + + newlat = location.lat + (dLat * 180 / math.pi) + newlon = location.lon + (dLon * 180 / math.pi) + return LocationGlobalRelative(newlat, newlon, location.alt) + +def plot_destinations_and_fences(ax, start_position, destinations, fences, current_goals, fence_centers): + ax.plot(start_position[1], start_position[0], 'bo', label="Start Position") + for i, dest in enumerate(destinations): + color = 'ro' if dest in current_goals else 'go' + ax.plot(dest[1], dest[0], color) + ax.text(dest[1] + 0.001, dest[0] + 0.001, f'{i}', fontsize=8, color='red' if dest in current_goals else 'green') + + # Group fence points into polygons + polygon_fences = [] + for center in fence_centers: + fence_points = [] + for i in range(len(fences) // len(fence_centers)): + fence_points.append(fences.pop(0)) + polygon_fences.append(fence_points) + + for polygon in polygon_fences: + fence_x, fence_y = zip(*polygon) + ax.fill(fence_x, fence_y, 'r', alpha=0.5) # Draw the fence area + +def drone_movement(vehicle, config, vehicle_id, start_position, destinations, plot_queue, path, current_goal): + x = np.array([start_position[0], start_position[1], 0.0, 0.0, 0.0]) # Initial state + + remaining_destinations = destinations.copy() + + while True: + if not remaining_destinations: + remaining_destinations = destinations.copy() + + destination = random.choice(remaining_destinations) + current_goal[vehicle_id - 1] = destination + print(f"Drone {vehicle_id} planning to go to destination: {destinations.index(destination)} at {destination}") + goal = np.array([destination[0], destination[1]]) + ob = config.ob + + while True: + print(f"Drone {vehicle_id} current position: {x[0]:.6f}, {x[1]:.6f}, yaw: {x[2]:.6f}") + print(f"Obstacle positions: {ob}") + + # Call DWA control to get the control inputs and the trajectory + u, trajectory = dwa_control(x, config, goal, ob) + # Update the drone's state using the motion model + x = motion(x, u, config.dt) + + path.append((x[0], x[1])) + + next_location = LocationGlobalRelative(x[0], x[1], vehicle.location.global_relative_frame.alt) + print(f"Drone {vehicle_id} moving to: {next_location.lat:.6f}, {next_location.lon:.6f}") + vehicle.simple_goto(next_location) + + # Add data to plot_queue + plot_queue.put((x[0], x[1], vehicle_id)) + + # Check if the drone has reached its goal + dist_to_goal = math.hypot(x[0] - goal[0], x[1] - goal[1]) + if dist_to_goal <= config.robot_radius: + print(f"Drone {vehicle_id} reached destination at {destination}") + remaining_destinations.remove(destination) + break + + print(f"Drone {vehicle_id} selecting new destination...") + +def plot_update(frame, plot_queue, ax, start_position, destinations, fences, config1, config2, paths, current_goals, fence_centers): + ax.cla() # Clear the axis to update the plot + plot_destinations_and_fences(ax, start_position, destinations, fences, current_goals, fence_centers) + for path in paths: + if path: + xs, ys = zip(*path) + ax.plot(ys, xs, '-k', label='DWA Path') # Use black color for the path + ax.quiver(ys[:-1], xs[:-1], np.diff(ys), np.diff(xs), scale_units='xy', angles='xy', scale=1, color='blue') + + while not plot_queue.empty(): + x, y, vehicle_id = plot_queue.get() + config = config1 if vehicle_id == 1 else config2 + plot_robot(x, y, 0, config) # Assuming yaw=0 for simplicity + + ax.set_aspect('equal') + ax.grid(True) + ax.legend(loc='best') + ax.set_xlim(0, 1) # Set larger axis limits + ax.set_ylim(51, 52) # Set larger axis limits + +def main(): + parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') + parser.add_argument('--connect1', help="Vehicle 1 connection target string.") + parser.add_argument('--connect2', help="Vehicle 2 connection target string.") + args = parser.parse_args() + connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' + connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' + + + print('Connecting to vehicle on:', connection_string1) + vehicle1 = connect(connection_string1, wait_ready=True, timeout=60) + print('Connected to vehicle 1') + + print('Connecting to vehicle on:', connection_string2) + vehicle2 = connect(connection_string2, wait_ready=True, timeout=60) + print('Connected to vehicle 2') + + start_position = [51.73, 0.483, 56] # Starting point for visualization + + # Read destinations and fences from files + destinations = read_positions(DATA_FILE) + fences, fence_centers = read_fences(FENCES_FILE) + + # Convert fences to obstacles for the DWA config + obstacles = np.array(fences) + + config1 = Config(FENCES_FILE) + config1.robot_type = RobotType.circle + config1.ob = obstacles + + config2 = Config(FENCES_FILE) + config2.robot_type = RobotType.circle + config2.ob = obstacles + + plot_queue = queue.Queue() + + paths = [[], []] # Separate paths for each drone + current_goals = [None, None] # Current goal for each drone + + vehicle1_thread = threading.Thread(target=lambda: drone_movement(vehicle1, config1, 1, start_position, destinations, plot_queue, paths[0], current_goals)) + vehicle1_thread.daemon = True + vehicle1_thread.start() + + vehicle2_thread = threading.Thread(target=lambda: drone_movement(vehicle2, config2, 2, start_position, destinations, plot_queue, paths[1], current_goals)) + vehicle2_thread.daemon = True + vehicle2_thread.start() + + fig, ax = plt.subplots(figsize=(15, 15)) # Increase the figure size to make the plot larger + ani = animation.FuncAnimation(fig, plot_update, fargs=(plot_queue, ax, start_position, destinations, fences, config1, config2, paths, current_goals, fence_centers), interval=100, cache_frame_data=False) + + plt.show() + +if __name__ == '__main__': + main() + From 8cead09e618fbab378fee880767b3eac7327536b Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 20:10:29 +0100 Subject: [PATCH 29/33] Update Unreal_Ardupilo_Drones_DWA.py --- .../Unreal_Ardupilo_Drones_DWA.py | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py index f09a99b21f..b0ff93064b 100644 --- a/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py +++ b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py @@ -100,14 +100,10 @@ def plot_destinations_and_fences(ax, start_position, destinations, fences, curre ax.text(dest[1] + 0.001, dest[0] + 0.001, f'{i}', fontsize=8, color='red' if dest in current_goals else 'green') # Group fence points into polygons - polygon_fences = [] + num_points = 20 # Assuming the number of points used to generate each fence for center in fence_centers: - fence_points = [] - for i in range(len(fences) // len(fence_centers)): - fence_points.append(fences.pop(0)) - polygon_fences.append(fence_points) - - for polygon in polygon_fences: + polygon = fences[:num_points] + fences = fences[num_points:] fence_x, fence_y = zip(*polygon) ax.fill(fence_x, fence_y, 'r', alpha=0.5) # Draw the fence area @@ -227,4 +223,3 @@ def main(): if __name__ == '__main__': main() - From d36cfe87c3506bdc7e9e1cf383d5d1a9d0546df5 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 20:59:59 +0100 Subject: [PATCH 30/33] Update Unreal_Ardupilo_Drones_DWA.py --- .../Unreal_Ardupilo_Drones_DWA.py | 55 +++++++++---------- 1 file changed, 27 insertions(+), 28 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py index b0ff93064b..7f57ef7067 100644 --- a/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py +++ b/PathPlanning/DynamicWindowApproach/Unreal_Ardupilo_Drones_DWA.py @@ -8,7 +8,6 @@ import matplotlib.animation as animation import threading import queue -import random import argparse from dronekit import connect, VehicleMode, LocationGlobalRelative from pymavlink import mavutil # Needed for command message definitions @@ -34,7 +33,9 @@ def read_positions(file_path): break elif reading_nodes: _, x, y = line.split() - positions.append((float(x), float(y))) + lat, lon = float(x), float(y) + if 51.4 <= lat <= 52 and -5 <= lon <= 1.2: # Ensure coordinates are within the specified range + positions.append((lat, lon)) return positions def read_fences(file_path, radius=0.003, num_points=20): @@ -53,16 +54,18 @@ def read_fences(file_path, radius=0.003, num_points=20): center_x, center_y = float(x), float(y) centers.append((center_x, center_y)) # Generate points around the fence center to form a polygon + polygon = [] for i in range(num_points): angle = 2 * math.pi * i / num_points px = center_x + radius * math.cos(angle) py = center_y + radius * math.sin(angle) - fences.append([px, py]) + polygon.append([px, py]) + fences.append(polygon) return fences, centers class Config: def __init__(self, fences_file): - self.max_speed = 1.0 # [m/s] + self.max_speed = 4.0 # [m/s] self.min_speed = -0.5 # [m/s] self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s] self.max_accel = 0.2 # [m/ss] @@ -97,30 +100,25 @@ def plot_destinations_and_fences(ax, start_position, destinations, fences, curre for i, dest in enumerate(destinations): color = 'ro' if dest in current_goals else 'go' ax.plot(dest[1], dest[0], color) - ax.text(dest[1] + 0.001, dest[0] + 0.001, f'{i}', fontsize=8, color='red' if dest in current_goals else 'green') + ax.text(dest[1] + 0.001, dest[0] + 0.001, f'{i+1}', fontsize=8, color='red' if dest in current_goals else 'green') - # Group fence points into polygons - num_points = 20 # Assuming the number of points used to generate each fence - for center in fence_centers: - polygon = fences[:num_points] - fences = fences[num_points:] - fence_x, fence_y = zip(*polygon) - ax.fill(fence_x, fence_y, 'r', alpha=0.5) # Draw the fence area - -def drone_movement(vehicle, config, vehicle_id, start_position, destinations, plot_queue, path, current_goal): - x = np.array([start_position[0], start_position[1], 0.0, 0.0, 0.0]) # Initial state + # Plot fence polygons + for polygon in fences: + if polygon: # Ensure the polygon is not empty + fence_x, fence_y = zip(*polygon) + ax.fill(fence_x, fence_y, 'r', alpha=0.5) # Draw the fence area - remaining_destinations = destinations.copy() +def drone_movement(vehicle, config, vehicle_id, start_position, destinations, plot_queue, path, current_goal, start_index): + x = np.array([start_position[0], start_position[1], 0.0, 0.0, 0.0]) # Initial state - while True: - if not remaining_destinations: - remaining_destinations = destinations.copy() + destination_index = start_index - destination = random.choice(remaining_destinations) + while destination_index < len(destinations): + destination = destinations[destination_index] current_goal[vehicle_id - 1] = destination - print(f"Drone {vehicle_id} planning to go to destination: {destinations.index(destination)} at {destination}") + print(f"Drone {vehicle_id} planning to go to destination: {destination_index + 1} at {destination}") goal = np.array([destination[0], destination[1]]) - ob = config.ob + ob = np.concatenate(config.ob) # Flatten the list of polygons into a 2D array while True: print(f"Drone {vehicle_id} current position: {x[0]:.6f}, {x[1]:.6f}, yaw: {x[2]:.6f}") @@ -144,7 +142,9 @@ def drone_movement(vehicle, config, vehicle_id, start_position, destinations, pl dist_to_goal = math.hypot(x[0] - goal[0], x[1] - goal[1]) if dist_to_goal <= config.robot_radius: print(f"Drone {vehicle_id} reached destination at {destination}") - remaining_destinations.remove(destination) + if destination_index == 0: + print("Hooray! We reached the first destination") + destination_index += 2 break print(f"Drone {vehicle_id} selecting new destination...") @@ -166,8 +166,8 @@ def plot_update(frame, plot_queue, ax, start_position, destinations, fences, con ax.set_aspect('equal') ax.grid(True) ax.legend(loc='best') - ax.set_xlim(0, 1) # Set larger axis limits - ax.set_ylim(51, 52) # Set larger axis limits + ax.set_xlim(-0.2, 1.2) # Set larger axis limits + ax.set_ylim(51.4, 52) # Set larger axis limits def main(): parser = argparse.ArgumentParser(description='Control Copter and send commands in GUIDED mode') @@ -177,7 +177,6 @@ def main(): connection_string1 = args.connect1 if args.connect1 else 'udpin:127.0.0.1:14552' connection_string2 = args.connect2 if args.connect2 else 'udpin:127.0.0.1:14553' - print('Connecting to vehicle on:', connection_string1) vehicle1 = connect(connection_string1, wait_ready=True, timeout=60) print('Connected to vehicle 1') @@ -208,11 +207,11 @@ def main(): paths = [[], []] # Separate paths for each drone current_goals = [None, None] # Current goal for each drone - vehicle1_thread = threading.Thread(target=lambda: drone_movement(vehicle1, config1, 1, start_position, destinations, plot_queue, paths[0], current_goals)) + vehicle1_thread = threading.Thread(target=lambda: drone_movement(vehicle1, config1, 1, start_position, destinations, plot_queue, paths[0], current_goals, 0)) vehicle1_thread.daemon = True vehicle1_thread.start() - vehicle2_thread = threading.Thread(target=lambda: drone_movement(vehicle2, config2, 2, start_position, destinations, plot_queue, paths[1], current_goals)) + vehicle2_thread = threading.Thread(target=lambda: drone_movement(vehicle2, config2, 2, start_position, destinations, plot_queue, paths[1], current_goals, 1)) vehicle2_thread.daemon = True vehicle2_thread.start() From 11355cd09a639c6472ff0516cfc90a4315629df2 Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 22:54:49 +0100 Subject: [PATCH 31/33] Create Read me --- PathPlanning/AStar/Read me | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 PathPlanning/AStar/Read me diff --git a/PathPlanning/AStar/Read me b/PathPlanning/AStar/Read me new file mode 100644 index 0000000000..bdcbb0e25e --- /dev/null +++ b/PathPlanning/AStar/Read me @@ -0,0 +1,2 @@ +python3 take0ff_arm.py --connect1 udpin:127.0.0.1:14552 --connect2 udpin:127.0.0.1:14553 +python3 a_star_varients_fence_hospital.py From 7e0575355431852adf25342c0d503f2ff5c58eaf Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 22:55:17 +0100 Subject: [PATCH 32/33] Add files via upload --- .../a_star_varients_fence_hospital.py | 131 ++++++++++++++++++ 1 file changed, 131 insertions(+) create mode 100644 PathPlanning/a_star_varients_fence_hospital.py diff --git a/PathPlanning/a_star_varients_fence_hospital.py b/PathPlanning/a_star_varients_fence_hospital.py new file mode 100644 index 0000000000..ec47af5567 --- /dev/null +++ b/PathPlanning/a_star_varients_fence_hospital.py @@ -0,0 +1,131 @@ +import numpy as np +import matplotlib.pyplot as plt + +show_animation = True + +DATA_FILE = '/home/dell/ALNS/Destinations.tsp' +FENCES_FILE = '/home/dell/ALNS/Fences.tsp' + +def read_positions(file_path): + """ Reads positions from a TSP file format. """ + positions = [] + with open(file_path, 'r') as f: + reading_nodes = False + for line in f: + if "NODE_COORD_SECTION" in line: + reading_nodes = True + elif "EOF" in line: + break + elif reading_nodes: + _, x, y = line.split() + positions.append((float(x), float(y))) + return positions + +def setup_obstacle_dict(fences): + """ Creates a dictionary of obstacles from fence coordinates. """ + obs_dict = {} + for x, y in fences: + obs_dict[(int(x * 100), int(y * 100))] = True # Increase resolution by scaling coordinates + return obs_dict + +def in_line_of_sight(obs_grid, x1, y1, x2, y2): + t = 0 + while t <= 1: + xt = (1 - t) * x1 + t * x2 + yt = (1 - t) * y1 + t * y2 + if obs_grid.get((int(xt), int(yt)), False): + return False + t += 0.01 + return True + +class AStarPlanner: + """ Implements the A* search algorithm. """ + def __init__(self, obstacles): + self.obstacles = obstacles + + def heuristic(self, x1, y1, x2, y2): + """ Euclidean distance heuristic for A* """ + return np.hypot(x1 - x2, y1 - y2) + + def a_star_search(self, start, goal): + """ Performs A* search from start to goal. """ + start = (int(start[0] * 100), int(start[1] * 100)) + goal = (int(goal[0] * 100), int(goal[1] * 100)) + + open_set = {start: (0, self.heuristic(*start, *goal), -1, -1)} + closed_set = {} + path_found = False + + fig, ax = plt.subplots(figsize=(12, 8), dpi=150) + plt.xlim(5100, 5250) + plt.ylim(-90, 120) + for (x, y) in self.obstacles: + plt.plot(x, y, 'xr') + + plt.plot(start[0], start[1], 'ob', markersize=10) + plt.plot(goal[0], goal[1], 'or', markersize=10) + + while open_set: + current = min(open_set, key=lambda o: open_set[o][0] + open_set[o][1]) + if current == goal: + path_found = True + path = [] + while current in closed_set: + path.append((current[0] / 100, current[1] / 100)) + current = (closed_set[current][1], closed_set[current][2]) + path.append((start[0] / 100, start[1] / 100)) + path = path[::-1] + break + g, _, cx, cy = open_set.pop(current) + closed_set[current] = (g, cx, cy) + for dx, dy in [(-1, 0), (1, 0), (0, -1), (0, 1), (-1, -1), (1, 1), (-1, 1), (1, -1)]: + neighbor = (current[0] + dx, current[1] + dy) + if neighbor in closed_set or self.obstacles.get(neighbor, False): + continue + if in_line_of_sight(self.obstacles, current[0], current[1], neighbor[0], neighbor[1]): + g_cost = g + np.hypot(dx, dy) + if neighbor not in open_set or g_cost < open_set[neighbor][0]: + h_cost = self.heuristic(neighbor[0], neighbor[1], goal[0], goal[1]) + open_set[neighbor] = (g_cost, h_cost, current[0], current[1]) + + # Animation step: plot the current node + if show_animation: + plt.plot(neighbor[0], neighbor[1], 'xc') + plt.pause(0.001) + + if path_found: + xs, ys = zip(*path) + plt.plot(xs, ys, '-g') + else: + print(f"No path found between {start} and {goal}") + + plt.grid(True) + plt.xlabel('Longitude') + plt.ylabel('Latitude') + plt.title('Path Planning with A*') + plt.legend(['Obstacle', 'Start', 'Goal', 'Path', 'Visited Node'], loc='best') + plt.show() + + return path if path_found else [] + +def main(): + print("Starting path planning...") + destinations = read_positions(DATA_FILE) + fences = read_positions(FENCES_FILE) + obstacles = setup_obstacle_dict(fences) + + a_star = AStarPlanner(obstacles) + + # Loop through all destinations + for i in range(len(destinations) - 1): + start, goal = destinations[i], destinations[i + 1] + print(f"Searching path from {start} to {goal}...") + path = a_star.a_star_search(start, goal) + if path: + print(f"Path found: {path}") + else: + print(f"No path found between {start} and {goal}") + +if __name__ == '__main__': + main() + From 1253ee5ed87fefb973dff0acaa7dc0f018742a0d Mon Sep 17 00:00:00 2001 From: Shabnam Sadeghi Esfahlani Date: Mon, 8 Jul 2024 22:56:04 +0100 Subject: [PATCH 33/33] Add files via upload --- .../AStar/a_star_varients_fence_hospital.py | 131 ++++++++++++++++++ 1 file changed, 131 insertions(+) create mode 100644 PathPlanning/AStar/a_star_varients_fence_hospital.py diff --git a/PathPlanning/AStar/a_star_varients_fence_hospital.py b/PathPlanning/AStar/a_star_varients_fence_hospital.py new file mode 100644 index 0000000000..ec47af5567 --- /dev/null +++ b/PathPlanning/AStar/a_star_varients_fence_hospital.py @@ -0,0 +1,131 @@ +import numpy as np +import matplotlib.pyplot as plt + +show_animation = True + +DATA_FILE = '/home/dell/ALNS/Destinations.tsp' +FENCES_FILE = '/home/dell/ALNS/Fences.tsp' + +def read_positions(file_path): + """ Reads positions from a TSP file format. """ + positions = [] + with open(file_path, 'r') as f: + reading_nodes = False + for line in f: + if "NODE_COORD_SECTION" in line: + reading_nodes = True + elif "EOF" in line: + break + elif reading_nodes: + _, x, y = line.split() + positions.append((float(x), float(y))) + return positions + +def setup_obstacle_dict(fences): + """ Creates a dictionary of obstacles from fence coordinates. """ + obs_dict = {} + for x, y in fences: + obs_dict[(int(x * 100), int(y * 100))] = True # Increase resolution by scaling coordinates + return obs_dict + +def in_line_of_sight(obs_grid, x1, y1, x2, y2): + t = 0 + while t <= 1: + xt = (1 - t) * x1 + t * x2 + yt = (1 - t) * y1 + t * y2 + if obs_grid.get((int(xt), int(yt)), False): + return False + t += 0.01 + return True + +class AStarPlanner: + """ Implements the A* search algorithm. """ + def __init__(self, obstacles): + self.obstacles = obstacles + + def heuristic(self, x1, y1, x2, y2): + """ Euclidean distance heuristic for A* """ + return np.hypot(x1 - x2, y1 - y2) + + def a_star_search(self, start, goal): + """ Performs A* search from start to goal. """ + start = (int(start[0] * 100), int(start[1] * 100)) + goal = (int(goal[0] * 100), int(goal[1] * 100)) + + open_set = {start: (0, self.heuristic(*start, *goal), -1, -1)} + closed_set = {} + path_found = False + + fig, ax = plt.subplots(figsize=(12, 8), dpi=150) + plt.xlim(5100, 5250) + plt.ylim(-90, 120) + for (x, y) in self.obstacles: + plt.plot(x, y, 'xr') + + plt.plot(start[0], start[1], 'ob', markersize=10) + plt.plot(goal[0], goal[1], 'or', markersize=10) + + while open_set: + current = min(open_set, key=lambda o: open_set[o][0] + open_set[o][1]) + if current == goal: + path_found = True + path = [] + while current in closed_set: + path.append((current[0] / 100, current[1] / 100)) + current = (closed_set[current][1], closed_set[current][2]) + path.append((start[0] / 100, start[1] / 100)) + path = path[::-1] + break + g, _, cx, cy = open_set.pop(current) + closed_set[current] = (g, cx, cy) + for dx, dy in [(-1, 0), (1, 0), (0, -1), (0, 1), (-1, -1), (1, 1), (-1, 1), (1, -1)]: + neighbor = (current[0] + dx, current[1] + dy) + if neighbor in closed_set or self.obstacles.get(neighbor, False): + continue + if in_line_of_sight(self.obstacles, current[0], current[1], neighbor[0], neighbor[1]): + g_cost = g + np.hypot(dx, dy) + if neighbor not in open_set or g_cost < open_set[neighbor][0]: + h_cost = self.heuristic(neighbor[0], neighbor[1], goal[0], goal[1]) + open_set[neighbor] = (g_cost, h_cost, current[0], current[1]) + + # Animation step: plot the current node + if show_animation: + plt.plot(neighbor[0], neighbor[1], 'xc') + plt.pause(0.001) + + if path_found: + xs, ys = zip(*path) + plt.plot(xs, ys, '-g') + else: + print(f"No path found between {start} and {goal}") + + plt.grid(True) + plt.xlabel('Longitude') + plt.ylabel('Latitude') + plt.title('Path Planning with A*') + plt.legend(['Obstacle', 'Start', 'Goal', 'Path', 'Visited Node'], loc='best') + plt.show() + + return path if path_found else [] + +def main(): + print("Starting path planning...") + destinations = read_positions(DATA_FILE) + fences = read_positions(FENCES_FILE) + obstacles = setup_obstacle_dict(fences) + + a_star = AStarPlanner(obstacles) + + # Loop through all destinations + for i in range(len(destinations) - 1): + start, goal = destinations[i], destinations[i + 1] + print(f"Searching path from {start} to {goal}...") + path = a_star.a_star_search(start, goal) + if path: + print(f"Path found: {path}") + else: + print(f"No path found between {start} and {goal}") + +if __name__ == '__main__': + main() +