From 7ece5bccb1e8f02f5e82f155af5d104925465f90 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 16 Feb 2026 18:08:13 +0400 Subject: [PATCH] add RRT* path planning - RRT* planner with rewiring for optimal path search - Simulation with search GIF and car-following navigation GIF - Test for simulation - README entry for RRT* in ToC and examples --- README.md | 6 + .../plan/rrt_star/rrt_star_path_planner.py | 507 ++++++++++++++++++ .../rrt_star_path_planning/map.json | 1 + .../rrt_star_path_planning/path.json | 1 + .../rrt_star_navigate.gif | Bin 0 -> 2045655 bytes .../rrt_star_path_planning.py | 111 ++++ .../rrt_star_search.gif | Bin 0 -> 8147270 bytes test/test_rrt_star_path_planning.py | 21 + 8 files changed, 647 insertions(+) create mode 100644 src/components/plan/rrt_star/rrt_star_path_planner.py create mode 100644 src/simulations/path_planning/rrt_star_path_planning/map.json create mode 100644 src/simulations/path_planning/rrt_star_path_planning/path.json create mode 100644 src/simulations/path_planning/rrt_star_path_planning/rrt_star_navigate.gif create mode 100644 src/simulations/path_planning/rrt_star_path_planning/rrt_star_path_planning.py create mode 100644 src/simulations/path_planning/rrt_star_path_planning/rrt_star_search.gif create mode 100644 test/test_rrt_star_path_planning.py diff --git a/README.md b/README.md index 7ffc9670..78645b88 100644 --- a/README.md +++ b/README.md @@ -27,6 +27,7 @@ Python sample codes and documents about Autonomous vehicle control algorithm. Th * [Hybrid A*](#hybrid-a) * [Dijkstra](#dijkstra) * [RRT](#rrt) + * [RRT*](#rrt-star) * [Informed RRT*](#informed-rrt) * [Path Tracking](#path-tracking) * [Pure pursuit Path Tracking](#pure-pursuit-path-tracking) @@ -129,6 +130,11 @@ Planning ![](src/simulations/path_planning/rrt_path_planning/rrt_search.gif) Navigation ![](src/simulations/path_planning/rrt_path_planning/rrt_navigate.gif) +#### RRT* +Planning +![](src/simulations/path_planning/rrt_star_path_planning/rrt_star_search.gif) +Navigation +![](src/simulations/path_planning/rrt_star_path_planning/rrt_star_navigate.gif) #### Informed RRT* Planning ![](src/simulations/path_planning/informed_rrt_star_path_planning/informed_rrt_star_search.gif) diff --git a/src/components/plan/rrt_star/rrt_star_path_planner.py b/src/components/plan/rrt_star/rrt_star_path_planner.py new file mode 100644 index 00000000..74feb733 --- /dev/null +++ b/src/components/plan/rrt_star/rrt_star_path_planner.py @@ -0,0 +1,507 @@ +""" +rrt_star_path_planner.py + +Author: Auto-generated + +This module implements the RRT* (Rapidly-exploring Random Tree Star) algorithm for path planning. +RRT* is an improved version of RRT that includes path optimization through rewiring. +After adding a new node, RRT* finds nearby nodes and optimizes the tree structure by +rewiring nodes to use better parents, resulting in asymptotically optimal paths. +""" + +import numpy as np +import matplotlib.pyplot as plt +import matplotlib.animation as anm +import sys +from pathlib import Path +from matplotlib.colors import ListedColormap + +abs_dir_path = str(Path(__file__).absolute().parent) +relative_path = "/../../../components/" +relative_simulations = "/../../../simulations/" + + +sys.path.append(abs_dir_path + relative_path + "visualization") +sys.path.append(abs_dir_path + relative_path + "state") +sys.path.append(abs_dir_path + relative_path + "obstacle") +sys.path.append(abs_dir_path + relative_path + "plan/astar") +sys.path.append(abs_dir_path + relative_path + "mapping/grid") + + +from state import State +from obstacle import Obstacle +from obstacle_list import ObstacleList +from binary_occupancy_grid import BinaryOccupancyGrid +from min_max import MinMax +import json + + +class RrtStarPathPlanner: + def __init__(self, start, goal, map_file, x_lim=None, y_lim=None, path_filename=None, gif_name=None, max_iterations=5000, step_size=0.5, goal_sample_rate=0.05, rewire_radius=None): + """ + Initialize the RRT* planner. + Args: + start: (x, y) tuple for start position in world coordinates. + goal: (x, y) tuple for goal position in world coordinates. + map_file: Path to the grid map file. + x_lim: MinMax object for x-axis range of the grid. + y_lim: MinMax object for y-axis range of the grid. + path_filename: Path to save the generated path. + gif_name: Path to save the animation as a GIF. + max_iterations: Maximum number of iterations for RRT*. + step_size: Maximum distance to extend the tree in each step. + goal_sample_rate: Probability of sampling the goal position. + rewire_radius: Radius for finding nearby nodes for rewiring. If None, uses step_size * 2. + """ + self.start = start + self.goal = goal + self.explored_nodes = [] + self.tree_edges = [] # Store edges for visualization + self.grid = self.load_grid_from_file(map_file) + x_min, x_max = x_lim.min_value(), x_lim.max_value() + y_min, y_max = y_lim.min_value(), y_lim.max_value() + self.resolution = (x_max - x_min) / self.grid.shape[1] # Width of each cell + self.x_range = np.arange(x_min, x_max, self.resolution) + self.y_range = np.arange(y_min, y_max, self.resolution) + self.x_min, self.x_max = x_min, x_max + self.y_min, self.y_max = y_min, y_max + self.path = [] + self.path_filename = path_filename + self.max_iterations = max_iterations + self.step_size = step_size + self.goal_sample_rate = goal_sample_rate + self.rewire_radius = rewire_radius if rewire_radius is not None else step_size * 2.0 + self.start_idx = self._world_to_grid(self.start) + self.goal_idx = self._world_to_grid(self.goal) + + self.search() + self.visualize_search(gif_name) + + def load_grid_from_file(self, file_path): + """ + Load a grid from a file and convert it to a numpy array. + Args: + file_path: Path to the file containing the grid data. + Returns: + grid: A numpy array representing the grid. + """ + file_extension = Path(file_path).suffix + + if file_extension == '.npy': + grid = np.load(file_path) + elif file_extension == '.png': + grid = plt.imread(file_path) + if grid.ndim == 3: # If the image has color channels, convert to grayscale + grid = np.mean(grid, axis=2) + grid = (grid > 0.5).astype(int) # Binarize the image + elif file_extension == '.json': + with open(file_path, 'r') as f: + grid_data = json.load(f) + grid = np.array(grid_data) + else: + raise ValueError(f"Unsupported file format: {file_extension}") + + return grid + + def _world_to_grid(self, world_point): + """ + Convert world coordinates to grid indices. + Args: + world_point: (x, y) tuple in world coordinates. + Returns: + (grid_x, grid_y): Corresponding grid indices. + """ + grid_x = int((world_point[0] - self.x_range[0]) / self.resolution) + grid_y = int((world_point[1] - self.y_range[0]) / self.resolution) + return (grid_x, grid_y) + + def is_valid(self, x, y): + """ + Check if a grid cell is within bounds and not an obstacle. + Converts world coordinates to grid indices, accounting for negative min values. + """ + return (0 <= x < self.grid.shape[1] and + 0 <= y < self.grid.shape[0] and + self.grid[y, x] == 0) + + def line_collision_check(self, point1, point2, num_samples=20): + """ + Check if the line segment between two points collides with obstacles. + Args: + point1: (x, y) tuple for the first point in world coordinates. + point2: (x, y) tuple for the second point in world coordinates. + num_samples: Number of points to sample along the line. + Returns: + True if the line is collision-free, False otherwise. + """ + for i in range(num_samples + 1): + t = i / num_samples + x = point1[0] + t * (point2[0] - point1[0]) + y = point1[1] + t * (point2[1] - point1[1]) + grid_x, grid_y = self._world_to_grid((x, y)) + if not self.is_valid(grid_x, grid_y): + return False + return True + + def get_nearest_node(self, nodes, random_point): + """ + Find the nearest node in the tree to a random point. + Args: + nodes: List of nodes in the tree. + random_point: The random point to find the nearest node to. + Returns: + The nearest node in the tree. + """ + distances = [np.linalg.norm(np.array(node) - np.array(random_point)) for node in nodes] + nearest_idx = np.argmin(distances) + return nodes[nearest_idx], nearest_idx + + def extend(self, nearest_node, random_point): + """ + Extend the tree from the nearest node towards the random point. + Args: + nearest_node: The nearest node in the tree. + random_point: The random point to extend towards. + Returns: + A new node if extension is possible, None otherwise. + """ + direction = np.array(random_point) - np.array(nearest_node) + distance = np.linalg.norm(direction) + if distance < 1e-6: # Avoid division by zero + return None + direction = direction / distance + new_point = np.array(nearest_node) + direction * min(self.step_size, distance) + new_point = tuple(new_point) + return new_point + + def get_nearby_nodes(self, nodes, point, radius): + """ + Find all nodes within a given radius of a point. + Args: + nodes: List of nodes in the tree. + point: The point to search around. + radius: Search radius. + Returns: + List of (node, index) tuples for nodes within radius. + """ + nearby = [] + for idx, node in enumerate(nodes): + distance = np.linalg.norm(np.array(node) - np.array(point)) + if distance <= radius: + nearby.append((node, idx)) + return nearby + + def get_cost(self, nodes, parent, node_idx): + """ + Calculate the cost from start to a node. + Args: + nodes: List of all nodes. + parent: Dictionary mapping node index to parent index. + node_idx: Index of the node. + Returns: + Total cost from start to the node. + """ + cost = 0.0 + current_idx = node_idx + while current_idx is not None and current_idx != 0: + parent_idx = parent.get(current_idx) + if parent_idx is None: + break + cost += np.linalg.norm(np.array(nodes[current_idx]) - np.array(nodes[parent_idx])) + current_idx = parent_idx + return cost + + def search(self): + """ + RRT* algorithm to find an optimized path from start to goal. + """ + nodes = [self.start] # Initialize tree with start node + parent = {0: None} # Parent relationship in the tree + cost = {0: 0.0} # Cost from start to each node + print(f"Start: {self.start}, Goal: {self.goal}") + + for iteration in range(self.max_iterations): + # Sample a random point or the goal with a certain probability + if np.random.rand() < self.goal_sample_rate: + random_point = self.goal + else: + random_point = ( + np.random.uniform(self.x_min, self.x_max), + np.random.uniform(self.y_min, self.y_max) + ) + + # Find the nearest node in the tree to the random point + nearest_node, nearest_idx = self.get_nearest_node(nodes, random_point) + + # Try to extend the tree from the nearest node towards the random point + new_node = self.extend(nearest_node, random_point) + if new_node is None: + continue + + # Check if the line segment from nearest_node to new_node is collision-free + if not self.line_collision_check(nearest_node, new_node): + continue + + # Find nearby nodes for potential rewiring + nearby_nodes = self.get_nearby_nodes(nodes, new_node, self.rewire_radius) + + # Choose the best parent (lowest cost) + best_parent_idx = nearest_idx + best_cost = cost[nearest_idx] + np.linalg.norm(np.array(new_node) - np.array(nearest_node)) + + for nearby_node, nearby_idx in nearby_nodes: + if nearby_idx == nearest_idx: + continue + # Check if connecting through this node is collision-free + if self.line_collision_check(nearby_node, new_node): + new_cost = cost[nearby_idx] + np.linalg.norm(np.array(new_node) - np.array(nearby_node)) + if new_cost < best_cost: + best_cost = new_cost + best_parent_idx = nearby_idx + + # Add the new node to the tree + node_idx = len(nodes) + nodes.append(new_node) + parent[node_idx] = best_parent_idx + cost[node_idx] = best_cost + self.explored_nodes.append(new_node) + + # Remove old edge if parent changed, add new edge + if best_parent_idx != nearest_idx: + # Remove old edge from visualization (if it exists) + old_edge = (nodes[nearest_idx], new_node) + if old_edge in self.tree_edges: + self.tree_edges.remove(old_edge) + self.tree_edges.append((nodes[best_parent_idx], new_node)) + + # Rewire: Check if nearby nodes can get a better path through new_node + for nearby_node, nearby_idx in nearby_nodes: + if nearby_idx == node_idx: + continue + # Check if connecting through new_node gives better cost + if self.line_collision_check(new_node, nearby_node): + new_cost = cost[node_idx] + np.linalg.norm(np.array(nearby_node) - np.array(new_node)) + if new_cost < cost[nearby_idx]: + # Rewire: change parent of nearby_node to new_node + old_parent_idx = parent[nearby_idx] + if old_parent_idx is not None: + # Remove old edge + old_edge = (nodes[old_parent_idx], nearby_node) + if old_edge in self.tree_edges: + self.tree_edges.remove(old_edge) + # Update parent and cost + parent[nearby_idx] = node_idx + cost[nearby_idx] = new_cost + # Add new edge + self.tree_edges.append((new_node, nearby_node)) + # Update costs of all descendants (propagate cost change) + self._update_descendant_costs(nodes, parent, cost, nearby_idx) + + # Check if the new node is close enough to the goal + distance_to_goal = np.linalg.norm(np.array(new_node) - np.array(self.goal)) + if distance_to_goal < self.step_size * 2: + # Try to connect to the goal + if self.line_collision_check(new_node, self.goal): + print(f"Goal reached at iteration {iteration}") + # Find best parent for goal + goal_nearby = self.get_nearby_nodes(nodes, self.goal, self.rewire_radius) + best_goal_parent = node_idx + best_goal_cost = cost[node_idx] + np.linalg.norm(np.array(self.goal) - np.array(new_node)) + + for nearby_node, nearby_idx in goal_nearby: + if self.line_collision_check(nearby_node, self.goal): + new_cost = cost[nearby_idx] + np.linalg.norm(np.array(self.goal) - np.array(nearby_node)) + if new_cost < best_goal_cost: + best_goal_cost = new_cost + best_goal_parent = nearby_idx + + goal_node_idx = len(nodes) + parent[goal_node_idx] = best_goal_parent + cost[goal_node_idx] = best_goal_cost + nodes.append(self.goal) + self.explored_nodes.append(self.goal) + self.tree_edges.append((nodes[best_goal_parent], self.goal)) + self.path = self._reconstruct_rrt_path(nodes, parent, goal_node_idx) + sparse_path = self.make_sparse_path(self.path) + self.save_path(sparse_path, self.path_filename) + return + + print(f"Goal not found within {self.max_iterations} iterations.") + # If goal is not found, return the path to the closest node + if len(nodes) > 1: + distances = [np.linalg.norm(np.array(node) - np.array(self.goal)) for node in nodes] + closest_idx = np.argmin(distances) + self.path = self._reconstruct_rrt_path(nodes, parent, closest_idx) + sparse_path = self.make_sparse_path(self.path) + self.save_path(sparse_path, self.path_filename) + + def _update_descendant_costs(self, nodes, parent, cost, node_idx): + """ + Update costs of all descendants after rewiring. + Args: + nodes: List of all nodes. + parent: Dictionary mapping node index to parent index. + cost: Dictionary mapping node index to cost. + node_idx: Index of the node whose cost changed. + """ + # Find all children of this node + children = [idx for idx, p_idx in parent.items() if p_idx == node_idx] + for child_idx in children: + if child_idx in cost and child_idx in parent and parent[child_idx] is not None: + parent_idx = parent[child_idx] + cost[child_idx] = cost[parent_idx] + np.linalg.norm(np.array(nodes[child_idx]) - np.array(nodes[parent_idx])) + # Recursively update children + self._update_descendant_costs(nodes, parent, cost, child_idx) + + def _reconstruct_rrt_path(self, nodes, parent, goal_idx): + """ + Reconstruct the path from start to goal in the RRT* tree. + Args: + nodes: List of nodes in the tree. + parent: Dictionary of parent relationships. + goal_idx: Index of the goal node in the tree. + Returns: + path: List of (x, y) tuples representing the path. + """ + path = [] + current_idx = goal_idx + while current_idx is not None: + path.append(nodes[current_idx]) + current_idx = parent.get(current_idx) + return path[::-1] # Reverse to get path from start to goal + + def make_sparse_path(self, path, num_points=20): + """ + Make the path sparse for use with CubicSplineCourse. + Args: + path: Full path as a list of (x, y) tuples in world coordinates. + num_points: Number of points to include in the sparse path. + Returns: + sparse_path: A sparse path with evenly spaced world coordinates. + """ + if len(path) <= num_points: + return path + + indices = np.linspace(0, len(path) - 1, num_points, dtype=int) + sparse_path = [path[i] for i in indices] + return sparse_path + + def save_path(self, path, filename): + """Save path to a json file.""" + if filename is None: + return + if not Path(filename).exists(): + Path(filename).touch() + path = [node for node in path] + with open(filename, "w") as f: + json.dump(path, f) + + def visualize_search(self, gif_name=None): + print(f"Exploring {len(self.explored_nodes)} nodes.") + if not self.explored_nodes: + print("Error: No explored nodes. Ensure search() is executed before visualize_search().") + return + + figure = plt.figure(figsize=(10, 8)) + axes = figure.add_subplot(111) + axes.set_aspect("equal") + axes.set_xlabel("X [m]", fontsize=15) + axes.set_ylabel("Y [m]", fontsize=15) + + self.anime = anm.FuncAnimation( + figure, + self.update_frame, + fargs=(axes, self.path), + frames=len(self.explored_nodes) + len(self.path), + interval=50, + repeat=False, + ) + + if gif_name is not None: + try: + print("Saving animation...") + self.anime.save(gif_name, writer="pillow") + print("Animation saved successfully.") + except Exception as e: + print(f"Error saving animation: {e}") + else: + plt.show() + + plt.clf() + plt.close() + + def update_frame(self, i, axes, path): + """ + Update frame for visualization showing RRT* tree growth and path. + Args: + i: Current frame index. + axes: Matplotlib axes to draw on. + path: The reconstructed path to draw after exploration. + """ + axes.clear() + + colors = [ + [1.0, 1.0, 1.0], # Free space (white) + [0.0, 0.0, 0.0], # Obstacles (black) + ] + custom_cmap = ListedColormap(colors) + + axes.imshow(self.grid, extent=[self.x_range[0], self.x_range[-1], self.y_range[0], self.y_range[-1]], + origin='lower', cmap=custom_cmap, alpha=0.8) + + # Draw tree edges up to the current frame + num_edges = int((i / (len(self.tree_edges) + len(self.path))) * len(self.tree_edges)) + for j in range(min(num_edges, len(self.tree_edges))): + edge = self.tree_edges[j] + axes.plot([edge[0][0], edge[1][0]], [edge[0][1], edge[1][1]], 'b-', linewidth=0.5, alpha=0.5) + + # Draw explored nodes + if self.explored_nodes: + explored_x = [node[0] for node in self.explored_nodes[:min(i, len(self.explored_nodes))]] + explored_y = [node[1] for node in self.explored_nodes[:min(i, len(self.explored_nodes))]] + axes.scatter(explored_x, explored_y, c='lightblue', s=5, alpha=0.6) + + # Draw path + path_start_frame = len(self.explored_nodes) + if i >= path_start_frame and len(path) > 0: + path_index = min(i - path_start_frame, len(path) - 1) + path_segment = path[:path_index + 1] + if len(path_segment) > 1: + path_x = [node[0] for node in path_segment] + path_y = [node[1] for node in path_segment] + axes.plot(path_x, path_y, 'g-', linewidth=2, label="Path") + + # Draw start and goal + axes.plot(self.start[0], self.start[1], 'go', markersize=10, label="Start") + axes.plot(self.goal[0], self.goal[1], 'ro', markersize=10, label="Goal") + + axes.set_xlabel("X [m]", fontsize=15) + axes.set_ylabel("Y [m]", fontsize=15) + axes.set_title(f"RRT* Path Planning - Iteration {i}", fontsize=12) + axes.legend() + axes.set_aspect("equal") + + +if __name__ == "__main__": + + map_file = "map.json" + path_file = "path.json" + gif_path = "rrt_star_search.gif" + + x_lim, y_lim = MinMax(-5, 55), MinMax(-20, 25) + + start = (0, 0) + goal = (50, -10) + + planner = RrtStarPathPlanner( + start, + goal, + map_file, + x_lim=x_lim, + y_lim=y_lim, + path_filename=path_file, + gif_name=gif_path, + max_iterations=5000, + step_size=0.5, + goal_sample_rate=0.05 + ) diff --git a/src/simulations/path_planning/rrt_star_path_planning/map.json b/src/simulations/path_planning/rrt_star_path_planning/map.json new file mode 100644 index 00000000..79434138 --- /dev/null +++ b/src/simulations/path_planning/rrt_star_path_planning/map.json @@ -0,0 +1 @@ +[[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.75, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]] \ No newline at end of file diff --git a/src/simulations/path_planning/rrt_star_path_planning/path.json b/src/simulations/path_planning/rrt_star_path_planning/path.json new file mode 100644 index 00000000..fce4eba4 --- /dev/null +++ b/src/simulations/path_planning/rrt_star_path_planning/path.json @@ -0,0 +1 @@ +[[0, 0], [4.75087218654987, 0.07895810741711168], [9.582869356011766, -1.0506567611604611], [14.114352936818678, 0.6439502740755565], [18.67372261735205, -0.006304262910310179], [21.34144317754782, -2.3197552417594336], [25.846605971495077, -4.388931138778045], [29.950736447698546, -4.04278169288967], [33.86200715713186, -2.499180139597338], [34.4037782089103, 2.249546008168026], [35.537387898648554, 7.175364663221906], [36.955413401808045, 12.982359157562843], [41.1508007268567, 15.033334469141959], [45.32268614027619, 15.769149518629249], [45.605148069872165, 10.080477147028189], [48.10681315024125, 6.434419004985622], [50.769896921715016, 2.5701130714834957], [50.34038694284904, -1.4179024281044705], [50.0881233442712, -5.288258291790932], [50, -10]] \ No newline at end of file diff --git a/src/simulations/path_planning/rrt_star_path_planning/rrt_star_navigate.gif b/src/simulations/path_planning/rrt_star_path_planning/rrt_star_navigate.gif new file mode 100644 index 0000000000000000000000000000000000000000..81f1fb81860b59b04317660debb3908bc227c6d3 GIT binary patch literal 2045655 zcmWifcTm$!6UTocfrOSu@1gf9(uL4F1VjWxsY(?P5K!PDA)$9gKm-lFD_sQCP(-?P zQ9$Wk1Sx`|d40cs+|At0+}zIX-t5e0*VxoZP2CLx#()z5fJ&wQ{rmUNpFij4=f8jd z{`KqE+1c6Y>FLj(KTl3hj*pLzj*bow4}bjlad2?3zrRmiS^56```+H(?(Xi+&d&Ds z_SV+c=H}+c#>V>k`r6vs>gwvs%F6Qc^3u}M;^N}huV24>`LeLEFh4&(H#hhB^XE^W zKF!X~e*E}xW@cu3dU|SVYI1UNVq#)^e0*$d?8Ao-qoboEBO`S)b=1MZ;o;$-p`n3+ zf&Tvf_wV0R-@c_*R}VHd_4W0=d-txlx3{OKr@OnGLZQ5U`}WP7H?Lp6?&#=fZ*Qko zRZ$BHsJXer#YNPd9BN7mH946YA5V>pq~5zX@^8F-o9gXN_41L1B_$p{V%*@P;jEwa3^o-=h)YR0Zq@={e#Ds)| z`1p7di9{q4V`F0p1Ogt9kBN!-@4x?|qoX7LDIz=~A|gCIJS;5i?%lf~AtAxR!FTT5 z2@DJj2ng`^_xJPj^Y!)h@$vEY_P%xN*3FwYJv}|acre5pM0IncIy+OZU86cVQO(S# z^72#=hzbCn?(S}GZmzDbE-o%NZrr$j{ra_Q*Bl)kuU@@sZ*PC)$`w01yUUj^+uGW; zVi*Piz{bYrwkSUihqJb}wz9Iau&^*UH#apkH8C+UGBPqSFwoc6*VWa?#9%N20s=I~H2nPhe0+Soyu3U-Jlx#eTwGk7oSYmS z9PI4uY;0_-tgI*&6dH|2p-@O95`jR#;c#YVW+o;kMn*;k1_l5Q(9_eyU@#~Q`cHIp zbhNaz5C{Ye2Gjgspnn2Dz&{C68LbTMF6-;!43*>*!2e$pJc9rX|7My0@Bcqc02mbj z!FWyT$z4PkiGVqx-SB{sMJe0aV*jzPPfh#d9G;67zu5oDcT^MYs z`S`-MCz;Q@wf0k!_hj|;q1L*&mq9Coh2}4xFLXp4ZZ8bIeDU=y9?ZyZ(N@3IlgJ`{ zW4Nth<$b2G`BRHmjcY@B7yP~qziQg}K-N#;w`_0TnykEBb7Q2vW#?nP$Iw&Dj@EB; zZ6P~fMmk=8|4Jb;3Rrcv9jx>}ly({Ie08`nR$~6l>UI0^&TNz4*U{Gbq)-K{ z-*lcGZcf&?e0cNv_s{*6p=Z`_-~9P~dbsoT!@r=U0(26KcnG`qA^|2=xfsi&vbjh^ z8c8gXSna)+;y79 zvb|Z7X(Y8(nr-j9RhDx7*M!R}7E|{BVIaw=uC}A1;cQq1LW2DE#RS>CuDn9%iW3h#Y393$d>D z>l{uMn`{4y&>ib|p6wp5f7Rj~(Ths4AJmEETm>=EGQI25nQ_J-IjPS2c)hsu%S>RJ zr2~WlgzLasLlidEb7{vwVXWi8OgVJCgs ziSX>xDHAa;n5O-ss1DH29wML++Jn0*w-KyZuAXd<52~;G-Nxp!h+?X1>0pIsnccC* zl<&TztPF)Z{9%Ryh$$N{?{OGxu1=j5!kXMTFR{>-KA*JEgE!e`vQztokWBK@{WO1z z;LB{DC~7@a-gb#G1Z#yEOL^*5o?E|NB+bo+?EluA1(${Of+kL(C_15}n95}kjSqh5 z3pw+4?M@t(Q%`Sw>}{-;t3SO@uMW3OCdWCEi)JhK50$AgJw_RedBg*w*?tRp>wJ*$jMbEtQaqE8pa~=>0!Mk{AVygho%t|E8=+o`H>cb5xPb1C?b4e#l+ERl!sQ`2?bMv ze5MycC|F#jXzS@yQLFJ={Y&u3(;f`G0b{5o^!^q-UMP=vy}Z9$H}uue&{6P{oXEv- zPqj?<88{G$_2dyZB9LnDJmrcM)>~Gk>cmcc{|`3s^{+1s0P^+mkSGydUTpm32=Mji zneOU5uR5gJt#fxo$`wHhnkFW_aRU|{nus6m_j;``O_3YA0pV%$-=2q49m=sJsEUi2 z2(;x0quZ};GgxpTY38yQ)5Tw-%$xc=;ulR9_QWzfzcC9&|AsQrsJ3l|@4-1ivbgE>%IIwb(?go8oC9KjNxe;D8IcPZIXvqPq;)uZJgb zw*Qt&WT|BhzX_2hyRuO+>Ta?do1YFz)`M3@WUFV)QmZPufub-ZmkVw~tV@4;INJk_13PmQS6=YTay=yKx| zoV`mrhAMm9Q~aFiL2N><-(JK;=Q%=G3`amy{UYfckkZ!ARKEcFtZ_8Dk(gCA(_YpOo^HC1WVQhjw~+rH!1bbWeD zt>p+IhP_%umic9EQVoG4>)wytxs9LsM*wyy#QSre@Xw-`FS;Q>^ zcyMv%xso_l{vOWu23Jnaytv#mi(zqF8m`&%b+r$#M#D!BpZ-4Iz#`hm60DAjdH!tb zL1}oleaasj_iZ61yUHr8j;pT~j`^#xObImIP3T_~xQT6_eQ$Nr_~g&7x4^GSJo)%` zPx%h>SvymX@XyvKnqLB9Ocx$C{Z#5IRE%*k`I>d%RFU?EVuH2FQd-lgf+)XYhK|Wf z(uFg5!!HWC@+NC>O=og9pDH{PFxenn_$3>6L!knS-HLAdB~!+)P!)J7&@-m&BUSW- zny2|SB=G0#;*FmJMXw+Ef6x6oS@_fPLx*4L+sMU-NvF|n|Ltde4_{mPvnPZ4FQD04 zbo0>g7pdYe^|0;(_r5^F@5?{_-WdK6alrHR{3QOZ*;pXYFJsd`_uXRd>>@xS z8~?d4$3%eeJzX)@diZcRe1SMVT|DMD9YKPCZ`37N7URRZ@Lg^MvpeuOjOkwj!CBFb zEzHeKgnkP^yr9^_iU_3}`0Goc-3cfcz{iY*L}oI`;?Y8FZ2WZYLPqY{i_C^N@Ov!N zM=^qU7vV)0$#@BR7(`pDfH+%ZFvfWG=>qbLbR~cpbrF7&3Dc@1Wp%mR908|DIvN5E zH51%r6fe3&suN83F~MAdL826(f}za!6|PcH03VVr1<7=Wa6^rgovmh?*RzRX=2bO=cN-f&maV(h{@dq8C5Pk%^9 zNDu~66@>VSXV68aRe};@O%mfbnUdNP;a$M*F}n5Hl+*^FLY1UPFd+9dejpEh9Kp@= ziG=_lxJ;3(c<9VNViE^MWRhazMc43Jf~#F zNE<=dhYhmN{PYM(gM-xI5l2A`I+)DI4QbbB5iX}`OL?eVB=f~2uE9QkaWS*(F=hiC z_#KYP)cc{>cve|ajz$;l6;TvNJ#=;-F^++9dLz3to@stJna`Sb70!0|<{Z9~z?@c*Qx4Wso4imVkoK zXF&(_=r3H{$EGZIk7)#T0cSkppGA1K!j)u2`bj+c?js*TR6#&jVbj$Dn7!xi8g@l_oTF$ax=B_{FG!7977a(pdpL2?PG{`Jf~!)p#%v2O#;pE znO(S=N0gf-fdc1rLerDs7tJ_nDDY@JIt^C*M)jFMLrLLMshkb4x@aSLhmMM+Nh;Eo z$V%zRBU@~9skcYNw^`lx5z0B}UJ7Hf4Qy@kv7l}`C8toZI>_ZS3fImRK8SveCrP^H z2j1ljI0K1yWj6Sf+#Td{OXj&(jgF*-(n+D{S2FG5@0hsb(HBhf61ML=u12LKa}_3| zlgaSnP&DHh{9ZHXX9`Rr>rtLY#oVhZu7j!^!5Yy!zy?KMvVrao#WJCRLB}3VP|w5M zDe=#$e5qR_qDV*0l$Xq6k{{%Zz#<+vL+emIPtjA922+dn`2m zN}|JMMfz%FtwgG6IJ3AidJT5+!br&XlTml zYUZ)gd6bXNU1YvK$Z2@LR6MKn#{DL)ie~nu<}^?%*8yzZ6_8v4_5s*~qB8NWvTKYD z3WBXEf-l*#fE_$c3IzRyxtw7GTU{*2fGPrc8l8twp-(sy%u(K%UXm!_1JdaMs*?CQ zllY`Lt^<`6$@y3s^^ROFNdQwZRu6Qma?Bp~Y`4fJw6iw6itB1eELBJ;GR)yxGP0^` zsvlKEzRJ(4YguZCgQ_Mq&?p6jgC^ITWOP@4M^H^TO-&uk4r|%{Y6(H;87BQ9s;-L> zUG8JgYt!V@)zM5{>R>9W>C`}jkjyV!xmNC@*Q+~8JPjjP*#`G(C6>U{AV`j4;h8u3 zw{KmwbO==%wami_Ea*+SiQ!FvR)@_d-$-bQ1J@z@99A zhy1suLzshtvZ2Jdb<>Rl-xXj|Hqg_>gq(v$alt0R&Q3W(cQl~~vPAcL43uWhT!Z64 zQXrT2Ar?Ws7W@X2l|c>%F-i$)^{lcZ@em6Wh0 z6x8Qk(C0NzZ|RJ>no^qHhPoWZzNpFL$keR&1YPOMj5lX@8>aW=?T_v3yRC)t_d^HF zp+czs?020BBSS2g%{zp3K|d*KJ_qlK1p~wa2#iLNyp zQJF_O7I0`3fT?&|sUn7{{ede*!z-zM1@&O%da!2Z5JVTe!`lyAK)#Pe56r!OtHq%k z#MsbpXZ%p^XfBpTHlk{`pDl{Dl+4WJjCLofT|Ji#_AEC4VVR?Ai_WCq82t<&XL@iOoKwaqT zBZPyG9%Hn!i?owursm)22b@zWBl%u@EN|l9N-i->EPgO5npm;;$iGDIt3`_*ZxA?d z2%aAgJ@^O_q)}@3+7bHf!ZQ~FTadrQz*vCh%tVCjv*u}y=6;*tp&med&mm~R9x>gX zci-k?2=kCT@ZUS>`QG!%;tS6tzRDDJ@kXJe6%gT%S%Hy-&P(VpzDe{!uMy8X_VJHa zMPF#TK!3()6QX;LEHhBg(P8`Dl7hfz%G2{ShzUSD&qu4VxPU<|dJlg>9`rf#yyqY+ znsosR05%K&^HYG7Ofbe3GVIDsH#ENax}9Y-OXoi{2*E6o;5p%BeGW{zoy#KxU!?LQTC#lQ$0Y9fc{?+C>ZQcml zik|`Z7x^>_UF5uW2~LTWqv*cLiMfHU!ZG`gqKqEB(4{skgz#<1DQ?`|Lv}c$U(39+ z|Bv(LH*T=SKu#(e4?NIYTIv|tR9M;^J4e{~p(krM4hy0Q+T7sX!Fp#jc#%0bbMtE5 zfUWFu+Vj4QJ>++P^g-?R_npt^8di`ia~TPp=Lyy>+RS&RRYoqW>u$3YF}yWHqtZ|^ zR)LQKkjJSU%PC%R@#vR;f!5M`{_yJL=nkvyq?p@ew_H~*|69`rhDqEe&p7D!BAwPa zWZ0RuJ%DBE`E<;eHwSN`7M|a$ljD992|C43NGQU-V`^1EAhV|f&oJAU6!#+v5#KD) ze`>zbBkl{!-)9VbCjK22NuH9_1(xdF)UqHisl2p?T?d7AOV7U53w_^}LhjSVp}KFQF`b7sUy>xLT+btEsYn-zEXILM7P4IbQ}Tgc z){&0|m`(Q!->)J&o!!LiyT%6$s@~5o=exp�K?&Qbc zlcO7~Tx7)PLv-92Tv44RU!ngAa$nc&P&}YCC~E(s>Ux&rx_Z{v-b@e z42$DFq9hUB>6&wK2{P(`W?=KF2smY>qP9d7x1dkY>vPYsfgDe+G5S443-2SmaV+_K z{rN~XB<5ogz%cs^Ii9**&hxj~dhk!+ARq{)U}I^S`3>@LOM3CleA*;Vn`MJ!_|0<` z2b&cmBJWApk_l?O9U^GSe$HyPHfSw={S5@~SvDvo*rFIauy5O(3ID6!&tyd*gQTHn*OWDASS;Uzq7tbDv~ezNO>MNRHzP-@f(= zkTa`$a`pQcLim}H$o|NLog&q4KW_iZ&4+K*2S$~LP>9zwR@csXmQTDqMhkf+9_@TQ z^q!D6%+>B+b4jauP5RSP9Kk^KO;_^TgPpCoFjauRY>h`fI@#|euRIld>ikM~wfBzf z6Q^YtuHNKpa=9ie(rKCWKVIMaWo{p|yY`GbVQ&8X{)cUw$k~s#wu?hyr}u4nbE5U< zr0*nn#%EU`=@UBtz)AF%8s_!uyN+^f(~;qv_-%Y>&}Z|G7nMP{qWAX6sU@c6_qJ1F z)Mib(;8&we-c@mWDjF5L9;M=gBpxTH##pt<>u@pt!j&Oa^-7*W3nmr?6l~{rjm6o5 zQBvH`N`p%z)en~iILjH77)=|2p<+=W>BTx;QvLU_rOQ{Z?#rbMfA%kgx z%o1aq@ht<_97``&Iaib&I<+xipbx5sPZJ<-`j{>cH#*yX16Ob+$~&nx7}kF-ZjSqD zdjA!}iU4~#cX{qx4fT)C{mzYx0*X&#jab8XzTv)b33{q6M^-Gy<{t{cnNMn3C|#)7*!@M;QzI3`B&)A%6>tV6WcC64v)g)Z zQa}33A2WuTzgN+9l$_6C;9^Clr z`~D>@tyQez=dU=E%tUI)xiII=`VXc#St)%A&#f4>=!;p`Sd9$#V+$LeJ(4-?&KU_( zhjRAF|Ggu~zwlka*?V}~inBhqvRaaLtXu1^8*pZm8Gk>i$Vln5m*Z2tmbj~d#@{7I zMTG{TN2he4Sd(7WA_d1GGy_dAHo?wyMIi7T%8;+7Ddj5ydkHJ#fT01sR3iUt36OrV zLzd)>jjg>hf@Tnz8j~lC63#OLe?h@U$q0iCCH4f@2XeU(3gi}^q_ls4h-586c_2Ye z&ffi*o<&Hpi52V-C0(wK!u|>7rblO*rPny&l<1kkz}t`>voFN--lL!Agi!pJlE@{U2J*BcQ}w2d&&!f8gx;xgiDCe|v<@qIAd0OBNMqR_f* zr7=jK_d^7J>D5H6Npp!n`+h7ZOE59Un{YudDx1sl$A$m?Q_3!pDHFz3nH5=NC$rJw z5r4BlvGwk3P<1>wdyo)rwpD^DOEY=bh`%VZBCv!ZL6J(y0iC|7TSOCjPX+tNoatIG zLqDe>28ap{E1|?}I)je2y#1zu`wOJva?~#aGQ*=vu;R8Z1oU1t>?reqv>jZ^&B2LV z=A-_m&~kJ#;Gw-eh(bb*Ua7vrXxL2CGg?{RPx~{~UA+MiQ*WNHvttQH+0v0^f;jp1 zGJ-d2mDye3GV@&aJF%Jj)@dm4=lax`2r!Zd!1EpzfrcM62y#dgoys(?w=^yZV3Eo6 zg1HF2JVA7^$eLnk{$M-hBo2GYO9QkBgvs@G+8oqi?E^!I~ox*7XpDX#wrP>lk*-Bcug^tA@B~H!P3n}2meJ16* zMiiPj`M?cxlzDZjv%D_I!1(aSE;FI23;+ZM+%j(DVKaH{72PkTaw88#0nUA@g_tPK zBAc~AM_}ei!uGEm%F`itkt{T_CdDu2TK^SUQI88kuWkqv4{4 zkn2ooVffBw+%)Y(fn0w@l8RTmqUV?aXvzXETVnXTb-JikxsoX37ms%wE>FKGAMyuj zq3`&iIljM!UdY#xMbq87b@F*`t$#vkzC+Nji}id$yKfY(eSTElT zw~zOmUtq*!q}5Zub^GM8DK4s6$I&f6s5Jgx^RV*^2(?cdy8s|0VTpbVr0Z zWH_Gx=j($y^Wd7=MaE|)ZH&ATFJn%cQxH&n*M#MXHxh>Oc1(K4V()-x> zf20R$iKE|N7_KnfP9!>ysp#}~J=_=0$e3JFvc51TeRC%tasJXsb)fS~<95WWf)$O(cW$KpbBb7EeDT|4s%75co}Cb{kFl~z5sQ#$QEO}9k}LFC-Xvn(kJJ5TciK+`O}jtqXHic_RJ9lC z!e93U3b=^Qy*a|2{cQ4D`yC9{IhD_i`YYjbw$#z_i`S;ZT}$!zYVDWI(HQN;=ZNX8 zp8My%@#ZX{Z$nNZ-li`i-mVB*g{<&s%MG~P|NS`TcBOG{I~7U+SScV83XL)aY(N2I zh?_n9#Wio6G<9~bb$pY~|MO5KW3F~=g2KE?fge#2kS-)^7fM7I#Uv8dq|pR^-PzyK z;-Rw}q$9Ph-e5-IZtmjg?c$x%g=pzUNo($CzG?H;6(Hy`LRvXf--?i6zalAYQz?Q4 z^bF2$ky1e^yKZS^wRde7JBXA%eD`CMOK%nRoSO7xl=WjxblD0xsB}?@^3L>Mc+!=! zG3r|SGUvLOW}P=d`s-V76tgdC)ar|Rc8fXpz(`4#3@&XS=;Oe>SSB5)h{%vfPa;mI zH>JmLwb>}NchOw`V$`JxiVnVq*CJHea=!ONhrZUX-bBClJ6I3>wr0+ScbAdM>Yl@K%tM=NM z24}JHEMYT9EisDd%1Qx zI1d!bz`{ZYt~jUXG4bSEz|*yul3hXR2K^Dp1b-}Tol;_{lT^9Lp!BeDv{rtQR?;Oq zqgVCs3xWod9Y9sXNir}nM_a7>W_+teB8eniv^!X|YjhSluu9RoCnNuy_aAjhY&kM5 zPQ-`JX2*^V&ZCDrqqIx3%*6j)+fJeL93_aPImm+1jt!SO#8i=&&}#d+R35G z^K$#U^Lcyp#QSv zwk9&gIh7(}DS4UpP8&1`M{A-nx@urGP%x}#kolI0wdu(6sg~*W;(ZtpVntbymi*$PbJcCj=fRL~jy=E=_c% z;^@DbpKOkQNwwvwijS@bNxz;b(z0QtHKvNOF>Xdplmipw2vT$=SV{KsqhT99HqDD{ zj0bja*#As$o&jOAbRVm2IO;ANo7;+7j&N>Wtc;i>OVEUq0Fwsm)1D~f8czq z%333!&zFvpNQgFpdhW+vHk`hE%<-{vDt_2j)^LzbeUcn8Rj?28U&K9a9_aBOvw!{G z@rvC^cGhds#E=c){dU4Ve7xLQ+^xGaw?u7R7Wy>bU4E0ArFS?E0ZmUh#QjH3Q0o_U zsAWM?D#<29RVN-`HeLgkWLrr~0^(JRWqqO(4VY*69-$PP#)>MZbAg2DQ?N!|3IiDu z*ai)rjT1mJ1Q%WF$&1s2V0PdMs_YYl00K378PWC_uaO)wEOKzAF%J2&1nj z1eaY+=(n@99Oq0jzH&G@lmt~|b9e=#^Tfm=+CbWyv2j-%Ne)C~Bn?V|crR~~I2Pwc z0b$zW?Kl&aT@zwqpOW*yXeCFI>+GYtkL^7pvbQr==k%Nw>?dH8ylswciTD^K4e1oB zHb#5DpDv9n5$;MGhJ#)s+W@X$-+HKTA~?1U0n_c8JM z_#DD1l$Q(UnFj$Bz`i(9a9)BmfcNtj2lk2X0H9i#L5Ls*e~T-%gbDORIaCt0E8}Ao zpqbuZ2@W3(kO^!Um}>+xzzIaC#Stj@80@uwGCN`7t->pHI%iB<#$mVGy-g9SOQ<6EG_0F~J)m?+A&;Ct%|f{=*Y#PZRDTJtHNc zfH&zKU*e?hJjs<1(pF1Ex(lf+SKa*@h=ZaeV6K^v*iE`GBMmX9j(|fPe!(5hooF27 z2_RP#Rbak#GcW$2oc5aE48;3mpy^Zp+;Ytoe#<{`rVkkxFy;}v=>d>Qo*07Hf9udT z{1*NeI^v0u7|bL9#wL-VXOehm`Sp0s!P02i&O71K>1ybekAt-MWF>r91cA`+1O$79^j$?=713tFbOuur4R=&3nwXBjfu8C-USwmau0hh5g3GdCzjY3e=~obmwUde*<{{_QjH!Bi11$g_or>VkSE;&|QOW z1;%S}A@=bD4-!G-J3m(U^ILB+iNhJg5B`h>)k`HmEl=c(9!zpDj~=_j|B=tMU?E{@ zKNEK#kaY0Ple60{m@dv55&lEUC0+VO>nxiFH4Pa;QuvXy*bkDjko##XF2JmCHT^>F zq2SBw7f*uQ7W)H{>)JmLwW)Nf&r-BrY-xzYH4=hp^Mh|M+}Y*aH2yje`(KFKcP4!S zxPf>`1BpRflm#!AUqp9|ammr+rqUZD_0s3GDyVru2AIh4HYge4l>v z`+;T44~H1~>lv{0`Ggz&i{`Z_#D2=Jy;|yBd7k@ke+_D^3fbCst!WR~CONa6~Ax zg>xO868`~l1-u>wnyy8sVti)&Bz^0Ypma*ecY(>CLIW1#Ef(+pmq!vkg-YU%8@`_z z6M*rdd$>v(QP9}Z7{O?FADdofOT-y7c zh#$8Ct!IBu34Ht0&Ixj9GmSbuye@XD7)bQY0stg30MSKa;5!c??+f-OqQ$kd53G&o zx#IthB(q7g_Gb#|cXek=J{*XVQ0)5k^Nz@Hp0K8(E)79wv_K==mV_rgw8$$6n_nGZ z>4u9wiH&czoszIiWWQ-pXBJdFUF#&O#8u_FV^HfFp3LWWQmZE-Ttgli7;~Fz3vQxY zoDOt(+j;+Z?}_;sUR$2tlKLtCbVlB)w&Snj(|4?%rWOw_RAp-ot*s1SxGj{!Sd_eu z(|;BgkENaRs3>I1xxR3}#koZ&d^kF7R%Lgdz9ad(`gi@_Vz4=6?xp;**44pW;hFsx z#(IVW{QN<#h5GtS^c6o`clmPO?=N5K*0}fJ+RdCi{U*efGBKZT8ajUbvI1MS z5K5*734cOUO^P6?irsDWzTXC>=)F*S1}?X*^g=QJXxbXR|DS=IrRkaj?C9IZLJq4B zO-E_%0=q6rh~_Z7u4kg&_zAPc#^ULXkZx0s8$g&4!~4Rd#k7qqaohf_#Cw}X%ET;_ zfl9kHmH60|jGu%V4>D3u(X+@)@Y77OWANG)Li@#SZ#yJqs+9Q2CbiS~cc+ zTA{wFl?ApTqf+rSm0$Th85W=3-)>OSUCMoX?V?3hQxP_0rpNKh@Hc%_h|qj1=guu> zowuo(WxNaX51FWN*1Jq)91@KL77l8vKBEYgx51i+<9pte&o}1XPu8USwKbWFvb!QJ z&rLOt0y2eUwWo#a#QtGCA?$KwpA z44S=+a;I0Lr@%eVO!Q5;;37AE!a={8T&_eVw3;sQtD@}C<6?ESEBf;MTZE24{_z&f z^cVY$9%&u>AN@H?hFs&u-{Y93uf@DRzAy8@2=OsRHp)5d=OES(A8r0*7*pjcMxHbPREWE zGa_=b2)>I_)8P^Gj847A%#c)R5G!&g=~mJbldy!eIL#u?sDq3g>DK=i+U>(PEX00X zp*1j49wSmJ#Qiv;Px%+ED^sewiAbK2^m8Unp5aZy6XQ|B&fee$?fv{LWSi z^50!*vxBH8*N}{%KMT{7vZbI`y7Ep{nY9p%WXz|W%Y9N0<4avdY9>spHYXl-PVr6s z^?vJRZ}t-6*f16A3gQ_sz#_ zATLt8Lz(uE(Sqw>b`uHJZd`Xr#GZ_V9*Ss@XQBJ>bT#P`O85f~)?6?yA_UosH$CH3 zE^^$iG}iYW4Cp4A97lQ6{n@HC=e|(D(c*S6+il~Y%<6%uleB75vdL6tEtdGRX#GkJ zeeH{FS)+3G_e#f+0-C*Yi)blpc8v#5X@|Z+gQm; zQ=N8Qm^qyPDti^5=kExJzTR)|nro&&PUkR|DSpTVBTj9oE%WY^Iu#i=|J5154k4eDyUz^xOHlT zv|WOuR+ZlizdDfTI?o%^i*OQq?i7_Ye3jkru|~$Jv8)(H-Cv>yP%l%wOdjq-UNG#^ zJUK93;?=_hz8Yd(Z!844#@?FOhl5NKnfHqlEAF2TY`)`u@+WMw#Qxqr7WTln!%h|^ zuNkKON;)P?Y(k9dQk7NfL2<&`!+h*gnqpN^lu$b#zxmd9NRe`u8=nJR-m*ZME7ky# z$r$3fSVhl+ek8BDO(*SST>XZjrtqFSjk$(gqm>_1EeLS|*Gsd!`3@le+M$v;Tm7_k zX_$dQemnimSwJB?$ocj1EltgdV`d8P-Z&G>YANi`CfMm^wD6&g@6w+p98>q}OL*n`w384BbaiO1Y3=8GTP?*jAI1S-ipxpeqN%vm^LKjJql1`43KsTmD_G%gJ==C8T(~e<>e#u@HF;jvs$Yf@=Fh%I3Ja`M1-2w zGeu1aZo8_3w2TOIvmdmRBfsBYjMn~ZIw+k;`Fsj2?s5PU}x|J1LtVeL!jJNvEed}#%G#0PPE*!DpMe9 ze-}wwEbna31v0*IQC}FwrT8rgG&4mnW&Imv3l96FlButuM%CwU=A(tXxtii-&cPxW zz<;bu$6xm(X$k?iK8Rq8zV4>C*oADP@YL$V^$hMhzh_vVLWB}EQtAC66xmYZdW4|f z&82nNRSC$GX$8T1ubGo)$$GWA+IX^F6fALH(2f}^u-Wsk8Z-z8r~&$|@9p;6INHdGfu&#y+F0+ZPQY9#&=R_$jpiHg%(tNRj zkgMz$7SmQIxpo)RTPwPM(TpZNTD2go*#JnHcyZIkyc}g{mS%Wk*4!-L2yP8@f-V^l z8SKpIJ9{K|MXaBS_+iV!&R4&y-@N25qG^bgJ_n160DXB~It7F)8aCES%vb(>ZtI_L zdRB0MuqGZfnN6cLHs^r0aTJ?wRJ?Xwtk=nXgtXeDh{sPUU@xkHFYT56o?nw&TjLiJ zb15%lxsJciOOxly%rxI4tR@CXQr8i6rAS|~4Qx4@52T*igK|#iJtqzk%6|ljy)3wC zemzI8PNOq>c z5g3){b+>rq)qz)+n-_=1dZbtqg8}$bo35qQ2jEms%?|%xFn^5wS6^hsqEE#pvjhnO z@C*}`6B$rG6!lfTSnbVnhmCrix1DRHOI2l*7GCO{C@O(x@#)f;1tpzaC;jpYAbSHz z8LGm*2DIxe(G)c+#Ul($&`+RXeWnzWlZZ=)?=2fSRrr9|U6tW94k)jOBLIlWqZK;0+PN9?hX5h{_W9_l2S)}>R~^~9Fp zpU8E#Hy!rr1#>_gha1C1El(BKvI0G@|bN~gMWKK)c0BhMPU;xV6iMO z3tYq!uiE-PV5%>vqQG&&yve zt;BxRB%jsTOi?bjfw@*$1&)X)k=?|l9lrlKKk3%SnbulCuzdfB!AR}vlYCSK0z!CnS>&(~Y-KI?*wG#$9`!bA3)V zd6~1@cCqqIl2=DYpQA;w$`;_RTlPRbjV1~IQ{(w*xfea?>1z6OmMV&tb9aCtUInB7 zx-Zb|p8th6S4j%Dbp?YAYP)p$IRnB@_MS*$h_cffT(eZPB5 z<4*HvU`*pd`i&s}*gGbU4SLA#3nB)vbA6^fA#U3{5B#~GJdX!J;mWkB=Gz9eG-p>_MzOD&##07Kpo~l43_D{mty_e6GoZcO>sDi{E$8 zA5;Qn75R4#&|(i>FYyErC>rwt3aVGpWIBm|t!ONT%3g|UGo&&4tU4 zVv}U}fhYj>tOv$;NAey;1Irg63Mf~;FzDFOR?Vf~>E$>F&o9|C^b#csl#gvg33bg@ z2C*yO*uk0#mYSkgUYBtz5E?9TXNjGmqo@D;$O_(~pnlPijMb9(>hIp86rp(eyO3Se zguS%^cd9@D?Pnp+yQX0+5|8g1>_4L}<#6?a6*5~4idzH+E*gX`LT|Cx{UJ(jia1LP zU#}Q<(J^3N#N6t_UZfBmPVQpqRM-?-^`^RX4C-8H@x1fI3uDwW_a`MD0=8yeo3aJq zPkPgkscs!DJxwna(STNTm5MG7t9Bl{us$`|!t0xR*XzUjZGD)`->%Ed6afjo$>}iX zjgvd*@L1AqrR8k8b3L8l-9=*IDC?0t=Cz6F^vZtt(M$n9MiB>(1X0-ngOtD-S z(flOv*DxHvqC)(5l>nyLx_hX+0_c2QiHxVj4_8TGz(K6_WjEmx7A)hX7WyR6WI*(m z_yb61w~j$9YkpgNNt-dM+%5S5qTa1(Pz{HOaJ{Rh>-?`rzA;NksaW_&L`I<6J<$J{ zd(WsQ8+Cv4Nq{7z(|cE{bX1y<&_Pf@P`VTqM8r^3iY4?8p{Pg=y<_NI11KOU0-{nZ zfT%Pz6cqu@M18mWJ?^vjnOXliv*!7(A6P4pT>0JCrGYPg>ut>jsdg75DWzdr(qeeh znSgU!l3dPs4Qx?7DnL0!|=q~7K3fRfy ztK@%a%cpCQq3s|)-|XYTfhRTa%-vILY&uIG{5+Y4qAFR3HA{}Qmv~?V$f%fJ4F@qz z{LVfjrV%~&UKI9b?Qavt_4%5c?WUfGDjn zvcKi-yg58Ha5iM0Sg6Okrp;GPV1%)HIs~+KTS=DW%4};awO6WcAJNbPl)ySfk$D3^ zj&Snh1-@pwb^9&)z82MMEuM?l!DzG>lUCrlhMG{B*$!0j_6SXjwUtShS4-+0$Q3Tx zvDkt0)^cqLJ+!I?Y@X&m{i>!tfF+%|dAH7?`?ebJsdRHX%d^o+Nr^xEj zv7s@=SSlS z#$*D=^@hPaE3z*)SMAt$bfQixL3JbJHaBbwuXl_4L^4zP3FR?kVw2OBbNjhoW|L5_ zm0p$MncayG==1~LCw-LDoMoxyiNkYqH%8uhSUi0crN%_nZ7pzAyOKs(QJ)Vcp--pE zdMwZ%t*Aa+7&2U>>#G+>sEiaF-{Ky5t2cVFFXLzh{GKmN!k5#)dDS6s+elf54 z#OAr-Z>k4At0t-Hs=^IaaTLZYTofyfxJWbYeo7 zz^Oq33a)giB-*s4ojiC$(SC4Kis_U^_I|%Z8K$b9hx2t2nvD0wURFgsk730V#xD#D z*iwwHIVjT&v}{3FLU>D49uX^!cZa{=yY6G3tNO51e#_>pV+){71vbzSBm`)sxZ%Nv zI`M~MZgV|Xd2na1PFMNzTMvRqKYPEC?L#&sX%#Q@Z~6`@YgbId?= z`_1zu!LkH#;>O|Y%uieH72fO0c0c*@x+v`e3~Pn3nH{3100p;MWX<0j`wZztFk+{OxS4o(;#FM1)YqGnK zJU$ZVm}HxXzApuhLlfrn9VCN3X&yQMLi&l)vG+}7u1xY|-m~J;<&md8+?3FClixmX zeY#>7w?lUI8;;2Hc5%ar7c1jt9UhkNZgi4r5PDV;xX%1qWIyjhbwnv>|2j$I!^G31##&1$PkZOK8s`5 ze5c-K6eK$=RaDewy)H^U^mx&&>E+b&t!{|yVog7KdZppGLdWT*QQzsaUX!&NA6gb` zvq#$G`=&p1eNDFh7)k%&NbA-`b{_9#J?!N775gY_@t#;p&ZE93B~EKY%FiCGo!S5B z`TC=#WzF?ryyA-ubHo0ejmP%qa+mv!55M>{dHRdhh5N^DIe&Rk(s^L*c`(LhGmPlj zv^kqvM*kLMedF-U;K$kdYFqCrj=i`zPT4W_5{;2EDN4gZXhXZfHhQ| z7o)S?G%-|2OHB%#mk{GKH9eG;cCB%KxAIL>3-L52iz)z)<1@2FTQWUWH!K7Qy@DS` z;%pL$FkxK3qRxr<`o=f>r-KhVKedYQ*f_}-@b#eEaQ%&5wYS_6!RAnHB2&5cG^9E; z-Z5JU5X|cW^fpC+7B-s!v{*#Ty zg7?Y|&(B+lCTA4y-n(dOm1TXcHlsxT{Nh13?|m9Ry~6ifK{4S3gx^jtg7NKySRbCA z;^LZwyJXj=^}s5D1Ir9bGl6Qm_=Pd9TKGQ@`jzXINToV^D+Q-|bp;D-%k*q3S!Cxu z>)UMW`_%Thx5n_>xW=8g6V_*(QxGE(|6r7>c!W z0bz-LGhw-(dG#Y1$M9AM0FiGX0RCNB4qD-Xy1Q4w|C*yH#I6@cg;fPW!Ojgj`eG9Y zeEpBhaWO3vl`$zt$@@CGumC66_zd=)W!Q~wpL}$N{s9T`4fa(M0ncIQH&YcE+0=LEz=O^AG*$DyAJ*<*)q6|TRIy1EcCMqh~0Nuu>1#t;QbTa0_BQ5&{)4F`Dcnp!Bar$uCy5xF=SkU>ej2$k{?XMlKD?*L+0u0nN zWaYCz)-uAKvj`Uh1H&8$u~!6VU##YRiD7?!F8FZ=E&&UMU7{ug*x+X9c^9naN0LH! zF+m0S^@hz-9rZ}P!d>NdVS(2nb(Ipr^(2lkqq?Nf%p#s02=0ifuRk${`|WOBjW8Rr z@D=}Sd;2V=Ui!x5_I~zv-(KnIl*!b5HB3m<7GlF!Q5fhvp z_9(JlHBT45U?{RZb+cPF&2sL*_f({3^Y?XnQ0Ge6BTZ*Jei(qIDl^O>+|rR>IA#w( zxZRS1BO|yngVhM)@OsGP)-Oz*?D1U*- zcM#w0M_;x+GAX~?)bS9Z^Y(sodi3r4tYGIk(Rr%sgKqxkzM`Dns&@_P+E`{ktiQvI zs@cP@=n*J=7R4zJTIg1#;KcN(s&9$npB16Glyfg=gE zBkWjTy$-ZgGfsbjl=vNqa2=fY^lluPfmgw-4N$|MHO&D-|+(M2w;MMs-lQi zT8ZhTayP9Ch2A@g^bmhaRpk}qS5@ZKN)@`L%y|zh4Dz@3pTWq816SO}g60HQt;C~1+ufBsK?yf3W8@z&1!#-tLJcUi32pcPj`!dIhfb{$^Z z%^LMVyZ3`H_@fiMq@T6Li8T?gF-e~_kpLCxD1Yg=dg-J!=~NY&YyL7f>t%A+WC~Pd zOZ;Uk>Sb%zWb0Jqn*8P3>gBrD3tjW)+D7^7k zSgcogzozhdRYmcWzv9<=#cykhAXO!n043H2CDghSo2oKbfHGf$ve3G+n5xR|02P@A z75Q})WmVO^0je4est49p@v3Tu0cxfVY8LBiR;qh#1NPcC>~&t>>!!NzWWc`D4g1cn z@AFgLe?DM;aKrw~>-)o0)uRH`;~LbH*40y0HLe9{+-%UuUDqg3)hr3ntZ2}zS=X#n z)oKdRYHQHyTG#4U)xH;?eZN8b;kx#y>VYQ#2PPX1yjVXltE%%RKxeT*=l#0Qs;cg% z0Nt+*y5H7yL25XbKpbl$4z+<}Q^Ruw;`waUnZQ51Um!Se3fLn6qyzb2L2%6fZ{>Ku z&3OM#i^p){b@y~Lp1+&%Iy*ZVay*9Y?zbH8Pcxpse{Vp*Z!O+0Azou+<1Zl|g+lq| z#H*>P`K`q(FE9UX#w%nz`8njme{073LyMP~oS2Z1@Jov)lq|$B<3&Y9G0b?sw0KED zK@2V4FDG7baPYr6@dyM0!-;qH?AiY!#Pj+~i0AJ9m+}sD5%_PNc%Dv9f7tNs?CgFE z@qXFx7#_S|61*b^O-WFYg@pyfgJ))D#!%rI8yg!L85tTH{<7ie>FNDlh|j^PkYjEHCgy7QYxR;iNCye?ITon+kvNv zQ@1bv<-N}nu9`(q6nt_@ju@2+>6H6a_u!MS_D1`M|9<0<+|!Lc20R320lP;1~5y6Ut( z%zsULJ}5l#3Fq_qiRiH4vD4d=pWl*WUf!H9eAY>>yl|s-YpGf*?@NAoi^BGb zJ4oROweel;b`h?BeC@-1h_&=0mFFf;h$U~vrB$ITx5ow^@Pr1N^II=o+RzYB>S~`l z_i9<7z4XJk%>;o1k5})4L5OFN(-u0pb^AR#7VbUV*xufJrzrDbYkiQOJEU*vvn3@p z$7ZSYCBgI?dH@%u-EDD0xfc*<#jeLKhHyS0L-zAle~3zn5Lgw3-Lmby`5!iE>dhSCEBX+Z~;1O42IoK&PtjWv@!|O_VSylU_CRe{^MQJs&`oahvt%G;HX84+QONtS+-U#cXmZF#ktnLd#Mo>sEo-A#+M>ej*x=ap_Kgyy zqzZFSv&UIe8>Q+GD-K;8e4J-J@3wnGCX*^UUikTao{>eRwbkHIiRNC1yN#1a%FLcr zI((|MdsuliyKuOMy&~FW_ZYp$VV6Dpguw}mDhD^#+cF@4nN9?m0iuz4jqdWDc6SXK zzp+ocLOBmi_BiYX6X7^_fln}Fd4|}kb+AdBgUq77)SYCc4road4K<#wCWuuV!stqP zW?JR3sa;f|T?=v-go$BSVHYU8AfjTlawLX6fy3B)`8aWa0oKj}h={bFTDUA0FxTf+ zkPef09tLXv?$KCW0t4!4$lF_7S^z=b=L>(>Rc4SDJ*aojyjzkYXA4ugNxz0GD15FK z#J>@1ojrp>KrvG93X<}1TKJ|hLKR`X$J<<7Q+)P|XTHbUnO$SV(KD~EW_X|^u?9NUjQ>eHf?eJOBva@H z03?v0GYrr3APfR1xe6BBfw(K{92vJFnb1){(P;J+VBo=y2ue`jMVOg;%LRDY854v% zlZ|q4C_4F`uo)E^N^qsigR%YS%|Wy+g$kXKb~J4aor?#kh<7BY5@a@f?mH9vJ)u4c zz%ts4*;O7A+s_8zP`+RyrW?Qs42BV#S_|&C5t;PN*ix=i3m-GfutF0@Q!WuDAo-VT zZ}5O(0xw;ZCsU&VGxnrNkSp*W+v^Y{n(WNfBP0Q#ibdnyb-viQ!<6(y!c#FkCvW%y zmUk60a#O+>C&K6KsJe4vqzfbZf|E}T{f?85N4Wwl_Jlr(N@Rll1`d+4U<7GTeC9h* z1mTAmCIKS|;|U`HKf44mNZ&C}&Ku~bUd?g&XH!vUJml%r=4KGU>W+Ao$Y<_wN;LiCB@ME}WydZ+_5t!@epvP(E=xx?t9{6wa{DS1_SnfoGof~0=W z!x36@;^NCQY<-23gyf;pDS^whkEL2D;$htjZ@{1)-Ki?KJu4BQ=F~o6-@IcS#3HtP zQMBp=fj}TbR2XiT;QcI|@#$Ph9LOXp49+lgmtulQI#graH5|91&jMId)h^6NU}0fw zf&i6&jt$DuD2h6-q@rO|0G6|48ZSK5#5G0*W1VLC5)00$?Q?~|GxWI>mAb`NR>94R zU_c6paS>TrXTI_DzFteON8<38;_1H0s~;bMV19{#trGmxYWpILp&ryOwTd0pZ0Q0lnVMYD%c4l5*P&-p z!E+?o-TfDFQh|3Ukb6xRfsu=k_WL#V80>z_wIk`wNyP9_v7ymnqf*WzP_E%8=#m*v zNfN=6jrBbt+H|+#$~^OU8GS^q)BF^*#Lg5F|tq` z2m@GCMOo8vtk+yw3q;{XIC!xuyo?C1Aj7Li;1qx%nL;$+5X}Tc+X&(j*5yzuzmO|r zd;~cPphjrOVJd2vis&FAT3r!MI7EXeqRuk9ngXX#5szsoFg;aiqu55RRVW~nWz!XV zY*r*Ii22b7<`fn4k%lIC;q6&0#_^#a_CrM}=!g-}vJ$JO8uUy(G+Y0&)Xu3$0_eQcCzJilx)gZJTh{Im;@JI7PpMPOJWQ04zg^ zbpwaYpMiH|V)JHLZxJvBUXV!w>jy8$IB!foTezJiyQUImh>(o%OTIOe+_sSXkvC;+ zg3V%+T_@AARtZZNCBeE=zI#D{U{;zsDG$&1A%@duF#K()g7;H*XsIhO5=WfmQ!gu? zUY4t_*jtpeJ(Fn)rU_V?v^NX3U0xh4i|p)lSBQ%%_8TEtXEFUInORRG!%8&uLnd^m zF5U5D{Qgl}Q)P#@*GMA+q)uCQT~|md2}viVzcoBMvA~}7TD)zX6XObTr6HKTAX@-N z!jGGG21>!9;lbcjrm4Bg?rs!JH37QlirCHWcS#vaCn5@6A-0TPh%;BFyl%vVU2rF2 zDqNxWEa4#()T>5rBO2zYC3MIVsSMNUIVE{2(kl2JWPplZCZiXL=yzC{ge6##2$ms( z_l$rQ0VZV}li^Gpor-Fu!2(=aR_|tJy8)Y2@qwE;gKgrcM04&2^MYboj=8ef5}1u$ znGJEwdRS(i8Kwgirv0u=d+C-;Dp)3^8L&JBEK34QF>X&rK&z`ckp*!Z_W7Sp^Ve?X zZ?)y`Oy+<8nh#Xk7V(jpm!z2-$nAb)SUVXRuK=GSSNoAM-a@-s3%IAaI6?~e+Y1Dz z_Jk4-32pJ+<}BO=mpWu$C@m{V+l3|I<7KuA9qJ32Kxi+PqU<`{zA3J;6J{DyT(X>O zu1|^%Di`Wa37oYpW_)XKii=GuzF4Us@sJtMUcQpnFf*HwlCdxyJANMHC3edttK;`2 zEZW(m8m(5>OM(mS9oyN|+e=S$7x}`u6&yHZ*Ngnxv1}PfLvXv?me}|6l_Uh0g)fPr z_m@X!iAwiy8Q{%g=u_p%S;B|ZxIN+vTUC#ygj8JdS2l>RFrSrGxm$4vR7lpWl(s65 zSv4!ps^nxVuk_})9Kv&CEC1?|Oa&KB$dtLaWuNCm_>h~eHoW=?_+joC9^HXcTB{NzI$Q6H!7r<*$VA-6`AtHlW z6ijLrTAne%LHtx zL$R1Z)6pudQb+whM3c&yCR7#Y_4ZPYA~HJ?O)^|qT*&eYo{ z)X68*5gpsmXPR^58d*xOTN&52wwT%0=VNuXAREtw)>qlW z8)tYwYe@}P32bEu3~h^nR`_Vs^3YCMHyOcI@Bz2bhW)DD;bS)6vb*^^y9J+j3-5G` z3N{^#zoWn0ChmA3JGyN+wDEf_#QEz0@erE{^^=X zL~%)IBNM(Yd5ag3NJ;qG%PLTOv7=r)P(!t|K5nYlPLRAeUWMVe|HZRj{Nh>U|3#iP zKl|hP--|u`Dn0x_TK|=2{eoGot*wlB!+$_pf9F~M3bXzl$s+#@JTU4GIXO9h1RgRN zPipe-x&tHa@Ec=Qo;dLb#`;xv_>Hmt=sNsjSpTl;;Nju%8)HGPGXJ+2>t7kxuc8A3 zU{Qsk0|4NR$1yP0VQWUp;m?)>gJJyzuzu64A3+CQLt)_qIt+yMUl`W^m~;4pUP(wu z{5|R*1A~G0|L8gZ!oaVz10V?esyp!T@%$oLe2l!qKLQU7m<4bF|AA-yB3XzZeTTmS z4*&!}fd7J7jK~832ACKq>u2c!`VXGf!TKLN4pwBad}`+X08bxGMDiaUhf{r?`%b^K zjD35&^*Udh3C?ytJ)-%q zj)NoCbHC~(go`ch<8eqv!xZzcjzf~wJ$Bfpm|U3m9hZ}$*>TV`T;SYqzI=3`{a44~ zm^5fo*A&$EqvP!aY**VkB)81CgEh<^2rxr(3j9>|qvMb{!i_`` z2X)(}3AXw!w#?BHjE+OW5xT}FBe!yb`&=BSR|W##ed$NXp-*hlK|H)p01d zmqRl;4p00nrT@S0IQ%Qm+IV{AW7p=}s*ksKJ}-Z~Gj=){D+};E$jF2&mz3d*cC8SO zbbRHK$%pt&qPj71amPz}J$+8bvY6sXNfBcUtM}!soJjYikKH#m6fc{sGa@zmH0Vj5 z*%)}}D*L%a;@YZtsT}yQnrem#tY%}(e1FZ^(L=_$GLhCF-zDUquyH;$qVlc$(=(DV z>Ov6hp&BHuE~)18)bY0uK2Ll0JFHLpd^G>^B1m`fQ|hjF^xXNvD^P_^2G6=8{Uo{< z)|6^5mF(%CEO+)xfxGedOsAC6vtQrlJboJVj(lA6;)2xSLtBgG>u&-wE|;NS@@d$9 zXm1RCG)`M-eTSAEQodKc{judTdM8j8bLZCE&OzVKBcx;TJ8R81(U)gx4yUXv^(6at zb&Z|Nw;59{*!O<@rK-c_z@{5lQ$H?oBsg#Tyh79K)~0i&cQ9QkCA3Y|zAKEcn$y;9 z``-a%nJ=9Z7x9zyphhDpVc0}+%&_sE_ogEXFNSO&igwrE=9*p-WKIEh8+2oZ%Yr1$ z3*gi1x|uZJD5b=Lu}vxcQf*4~lOC4_-`HN8u<97x51!>_sBdLYhs)VG$Lkt7AiLE6Jk!>9mhN#=p$UKN%~YTUX={% z*Ssz3s}d|hCVLsXThyfxA3S>kHXYF8Uvms{;^M{JAGpB68Ox z&sxt}FfY@5c7OOn`+6=du}u4&>7$UT^}NjoW&f6E4UR->{=u^ryeccK)VgbnPQfAB zIB&^ssT;-nm}cdz2CdJ^l-`v8i)XpW>F;~EcxQ&mB3Gp%O6R=ww{Um~o_{{ez(TgY zuY6qM(}pPkbnCj3*nx}!0lK=uen1JO?!*k_SVrLi0;1Zwse&JbW8n`=3ce)4ty5lU z^C*N=#rd}OzTki@Kp?uCpRYP;35D=ep43`110qByQ;+6R)`^*0UJqeF;B11}r5VUY zYPge_<1t{T2+0eR2ls_=8MMybI%*N)g3@9GI=i`CxvG-Y1t#O^fGC&_>#?JEM<1g~ z@H=B+fVxtAV2%fu)|4!NhFHqUO(d{iG+H~nj%7-CUc_OdGK@Lknyj=w%L}r%_pxPL zfGj3tD0)U59hOWeb_1om_Nywe678$SngeLj8r)XIum?@e$9Dr-$W^}ZpzDHOO5Gwf zw`<^C5usO44z4F(i)n1nll zNJQjziV^G?Pa;6&y`Cxz@XiPs0aVostVHb%Fdgs~?e_vvAmfs6MMG$KUIYYN87aU2~%^14?l0_ltwvAOOsGF}lpW zuFOjk0FYLU@0GwJOsAo`6BOdrPJPk$BxCiX7Kqu~xWVUL@gntNnfq7VfpBicf@9f9 z0kODSEq0NF8f9o0^NdIq3sHK5VtWY23dAln;dD?-PjNl`j^AP`?NLOdop8}zK~$FS zV$oqFQRdFidnwD_QCB(bS}O;jI*{*}OM&ivQ7loKAAqwp+)t|(higIOY&jF~FW8ep zUv3Wxu>k{Nf{Ul_-ssJV4p7G_J*Uq!hrQN*r}_B2*jb$zS8Zx|mcXot(+tql29FW0 zE}C-eis}s>J}D1SVbhDvJ|N<%^qrj7Xb_dzOBuowNkzPhHE8d5gK%t$iO4c|W0qBd zNF)vxH=@D+auveSNJaWD(A0Gb!e!Nahc%h0Tq9I4JEdFb%ES`tdRmj_2C#z{Y^N`t+-ccXj30N_9EJDK%d_Qs{qkdMhD|wvq?d5 zys^qD0rOxzU;wZD7N58j-*Pt`4_2NSO?I!w1CCrhx))9a-R0Sub!5@gdWm~l(D1au zsK4)PRKzbvY%mant@jl z;Y9#EUx_tk1{P0*MTx>90M^P8#0b&0lZI)w3@h>D8p6TqU9lQzSbzYg5p7=r$R~_W zf+hNi5|fiU|FJM+3RdD2Tc@eT#&wMD zhKwU1Ue6%jQqg^`=s^nBoXWh4Lye1Kzs*GZny_Y&S^d1&oLG{%|5;1eR!U&t`Afkt}6<{|(G%TJrZ9%*DMa>#?@aXo=58 z5=u>y*b0)Z{kWP)NcUL8tQ`pwOq%t=%x9*=WX4*%C29C^)z4f8uVS`mk`Q&w2PsT5 zBdnX7(L3sFZOmN9R^jE8B&Iry^d#2(9jaQ1l}>_piJD3^nJcI6&7$AsJT?liq(R5K|ij_5qLTgbrFYnOM~23ivH3M&_xlRL{v26 zg`xyMvY3(V$5l*&lax??BPc2fT0_7nL4i>!{0bKNoM>B(gHwptll-^}EfGO9^!pLi zJ0Fd?qFbD6+j1UE<_v$$ z8R5$v)5smS&wU!q(23_xwdFpa%zgPacZM%-j;@h6Z=d(}z6>QWFA;QYsf{Nv4ELTd z-!3g;t&LOCHvc>*b(4=D*OdRgV%N&o{Nu`LU?;GKvf1AIYqW(C!?o0nJd|a zPaNLIC(X%Qz#q@E(NOxtysx9FoF`< zTcqwF_4!7T_Eb@`vb9%g-uqxJeOqqqR<2JEE;vk2Cxr9cWU(cGiS?B5UN}FgF;``f z_l{bLlbJxbsPZ$JgU+%XqGtR8Y4Kx|1s?6CK2x%>k4u&C=>*NPK!-BORf9FmFLe{Mt^at?g9;;L?7Fn%9d}Ph|!DvuegntDkOF2IDIq z-!D!~t$Z$9`aG)^JQ}-{RdUavD5J7=Z7ct{=B>|W*hX3IbWrh};6<#_zTAl1x(O6f#)?QcJ+ft7=_hPNw0k@{P*II?QZWY!y zbvN~kwc6;lmb$g3svumo1RgWjkPy4Y~u@{7P9tv*fbnARU)8TTgx}{YzbdXJGxihN0 z@_}6L07pj+cSu*$VAqmE!RNu&7moQE*;O+Mioa2j*8e^#n)`pR3pzMB`1kcwe^1Z9 z<3ycZKXy-yDCqCbCxaG!|5*q9V*oW96-D>={|$`(Z_=WFErR~H%qTrI`Bx4!DJki% z94Mm&8Wa8Z(bI2Qbm`J1Mhf)T?uiit{bvg_@UIr=pSvf|f7v~SfgtC>|Ct#%F*Z;R z4u6C|$98kQ27p@tU}J54UWn`W28s~^{k48#R6zepj`a2am_Gfz1ggXvP=Fcu*#!L&1^tbRF8=4~la(l- zSzBC^eM8X@i4Dpl_VH-63r>=_s#id@-zAP6UO&EJe7m29tFF5 z6{mo|P*Gh=bO~%YM5ezm_i%aUx8sCO@?< zA|+w>7YXrfm!5Bxc}j>a{7io8>I4}A3kc5Fo)MitlAqaKMciGNwdmig=Vg8-KiTh& zJ0G(6l74xxVD*v2p50u(lAngYrjcZStxJqjWFVixOe7=uDIT=r_JoNYOm5K!5$4wq zK_z}BKlK9b^*vXV4#^jf&pp(oT?#9}pFc2;z~37$XCyzDY>X84jVg~M!J|Y66km?? zqE!<}WOux&oDZMAFGK}Qsl)ufP4y|hcKTm%CkEn>Dc&AaBd3;v12vva@tMz) zW8k{Ps`9!I*z$)LG&h%pZskZ~Wd*@Cfrl&=-ftY#KJrDa%=DPL%&5^v;)Y?m`TM>4 z7H4+de-^c5?)8YoY}8!Tu%of`^h|%(jYd-TZg%z@UKLYIdfyfrm*}fmX`QFz`Dk*iW^0+E z4+&|x+JC5Sra5%#;s^M)|B=v6CWR0hQtMFF{N2ZPp=%HJe`Kibb@OQ}Dk#NopC%%* zLq1P*40l~syQ-*@JCu_D^wGZH<5C~qwtUpFDZG8Ie$QGqa_82-vyVBS_U?W-&%T8q z1E$ewIdy3{Sp_%zR>jUB!l z5hpGd9Manz>qCiJ=@CVGs>^eaQEa|4Jv!mLNjgTOF;LN*J{>M?khu9s67Iwac1yb} zUi;=sk~f)STmO!!1tDId(R3$mxBi|GWe;Z`)~#|d?m!$Z;ia`0|IH)Cd)rr&2#H04 z?@anNr<7d`Iz23gV=H#wE{+SyiCb0LeGj*`93LHMu5d}JMk&PaVq9YJrA_Jk*Eao* zcvlxoa`d-bgsi2v$p}dso0{by*(D*eZ#on%)@WC%*xk6aTYsN%`jNCsQoR$8cz~(0 z@!Hyro^Uc%n)N|AY~AMO9!Wi~`)M6A>o-S=O{5g9kv9w<+tnrB7(w2A7@Iii@HT9a ziKEBtt;M?238g&gnz^AfA5Ld8hlw9eUKmz8e?)9{rPgSm{Dmzy8Cv{n$s=XM~ zr^_J^n)bnqeUqx*#k0w@m6lYupDuU)BHLokD^I?JTIpu@v+8b#-io%U-l#2_=+kVj z;J;j*yD2j{Sot9Gx~_w&Gr55xd3n8+0LaM!eZeI40ho(2`h3nDxNLV1v(1nLf^iyX78F5K}_;9Rw%_4;DC@ii{=A11lEZcI75im&RgZ$cn4lE;Amqc6+MGBzNpg~W8KOv zWK4i)d8aZyU)gmdqG2I0O0t0lugV<)e%#e$nStnntt-Zj@M%3B2>LIRMv(V z6+G_FCS^H-S~-%a)OuaGg%XC$!o%gH)Q9--hj|`=Fs?9n1-Db!kjPmWK$_(P;Zi^^ z{g_)LXM00n5MT<2W+wNeu0n7MEIJJcBI#MRhHGv5Oy^Y zFY1874;Uxsr6G94;B&;wJ>Aj1(=p&}NQ{sVns|68oUcwA*O4CP`?N5ICmx59pC<%P z6nY})UhR+fueta~PO^!--3v^(qM<}S;KfAmo15=_0NnNpRJmI>mMF|hdHx>857s?| z`|`wr%y&zg=<^jla|fCSS_AO2x`{#e6m_USCRGEBN!2BgU^;AFeatmncmBtu3ioqT z#q7rBeY{s|-Zh+?9EN@_6hoJ`A+Ve_2%WkC1@>fiGjR`u^VPrVR=rfuq&DNqd_uZk z?9jo*_Fgc9Fe0mQ0M01%`xiGN6mTIUMM|AxZUlW^^}YkW1XY6d5z+5yNFoVvgFu@_ zF;8hMBGDkS5_%1XO2v5qq7cS?&)X4%6H!>5gj^>g6@`6-ncaNxa$#T>->PRyV`*`-{^La%dKSrkMcosFbZ+(&W9O;PkX z0ka&5wV<%ZwJ0jDien?yb1q0z$R$R@%$4eQVCu|fqx%i5GAaROooAd2KqE>6(yqx#L!@; zF)Rgd=^OOB+5RmyM;ne+Pq?@3Lea1IphTLiUQxYyS zAi(p4;E}J_ardvES!5OedgD47W5SwxZFlMi5Mbzv?W@Bao5W(NAUY9hc$)PS5w!`s z&ONJcVal=KhG8DPnM6%T;sHsrXqT&CtSkE9XS@63oUaVH7G_aJBgj=O#@smVL@;)t z4!kmxFl-5@%ig0f_!vg8A@4o2TB z3sJTrwhNq9E59UG&OD3CK3VQf$Dd7H5**$rPm7njs9AAcQ#LfDV()5d))G(VWCd|5 z%e%);5MN0SsSNL_FnN;}npVL#8>6uoU%4b}TYThhWaaZh-qd(TG*T)mp5t2kk%vTR zmwQ~-6!vNe2PMABgUPOct9pcgkBuI;dAIp!NX==n%84b;^G)2fn&q?UH>SP0QtS0Y z@$s+Yxw^AzSEgz|R4P0*C>tK+g?%c$KgIh+vvfm^KYy$C`x5r7A-_^ZY0u^@D||I1 zn*#5kAP*{)PEn%5DaWR6VYk^gRLNXJQa5@k`4Xy@r|Lun>OZmPB**HBJId?|tqg|(#P)cry?)uIV0ssO z6-VyDc8}%SqeJ!^b=6|xZAzmZ%C?Q+^&Q-7l#$%y*4Y_=Ay4*P6I!L)TOw5!Ci zc|xwEsH(Ai8OuZO=t>N2oXf^$OgHN~-Y(g0sR(Ue8fyQreS1yo&W7Wi&!KlVv+rzm z+}WAF^L_gcAV>vkQ<?dUd{sOrias$+5MjG6ArKiI_rY7;-x$r9O( zTrN)~tL8Cf1Xjs?ulOGp|Bfdb(M+oN#C^ZWP?v}2uFun(L2ir>9`Uv0> zWnS>hR81dIT9Iuf^tH?#1Fv?<3ikVJ_Xj%lU%1pCl-N^vqBpkcZtzb3S^hgBK3xbz zXH52CyKL;JB0>=Cc9&>g7U{zly;7UtLw(mlNlRBdz0;PuGm!TnuTBeVzH=Yq*x}z% zeuxA6*WBvmKNy-2_;2Tf-*yOzZ9KW$dp0enj|-q%lTUjO)PvFuJ-E6!fnc?brDr zV{uhkU0G34@%P)ozcaM|c64>^+BL@cU|L#QIw|Q-j20Uk7ZDK^^UvGCf5m9OcUOUd zf&TvfzjjxDGPF}a7~0=QSBzXZJn+9~Xo3GYA9Q3q_V&LH2Y+1+Qsso+`~+wWbmlE4 z^6P?-LC?(1&Hp$b{B=9{`*2VniPX{kF}(VHJE)+k@b~jUH8nNH`Jj@LlA@xbf`Y=H zJ$vNjumG^QII9}%i*aWd%+`r zFti)7zV&K*vHd+H0QYHK5=Ax0!=x@a4L1H}XtMXbbd!X?LMs^Qo_WXzidl2@WP{h^ zO6Q>q9u4vEVrA9UN7Ki`q^Fl&47J>Pb%&^2sLVU4Sa3y8FKBNi`=ObBlElG0^P6t+ zVP2g<>rvx8dXAJVVaHAIt6k^f6I7amOvp7>*F1jCt)857E9oncCQqot0X?jjB33pzu1Zd$bVtp)a#xPWarY#PHXPkQ3f-e=@YgFU71QNSQ8=zSEeroWT*HFHFii zzcJ1Smlf3yh*yWmATy?%@4f$VJ}7CzEzD_KmgWcj7LcsKxuo(ycil2G%qWUAFfW|J z(B@*#e)E`%lL}c+A?#}YF}FJU>8T-8?e$}cjPpT>a1n(lTfESep=*+BT+{1R6Uo!r z@=V>Ii_8y5GG|=u-5pq@-%0UIOmn)hc+#eIkKv&Vh=okPDfH~(!)xf&qPI5)eg9x+ zkhGg5>wnCx7z~ZuyL^90=S|Cyn0-qNMI<8zL%Yw4U;M$)tnDJamKMv%{22y+F|<Q{NB5~nL|=%Xi6XP|lEtv8KK}^{ z@`@^U)YjMxROjYB`l;eTg8N3rA^iiSagW}ur_b_Fb?r4uYphv(ax=QdYS#r%`e5V! zWTC7J;}M_ERu*!I;m;SCJvh7hdjG1%<5#3(zHJo_cOrwTKRNquCg!DUJ}|!-<9l&- zZ{6vwr4fbUkg7sC&wRJvb39AxC=Q=lbTz;9QNdljhv)FMrM~>?<+co|k2~vI zVrkQDx%w%uKDLJYeyhnoCsOaZ@5M~lYWMci*5>a1qmm`xKpHblsj1Hkw+}0`oeI6*K zh|_GZEGAx;qrxq9zn2wX* zH5W(bOm-2|`?rNwB{4aJaFpRavn4~H()ePjNBG+T`hD;3eLv6Z z`9074J?DS($N4(ucpo4B4CC4-cVB(^0lXZwl`^7r;kq@10&;O}g)g)M2H=S1~%zM*FGv%rKyxk?U*^s%LXJ(W9yq*cQpFNPF zQ+*D1J{L)z*4vt97Wk@m+dj-PjI68{=n`YV9N`$eB%`$DH10sxwi;37Diaiz?#wF{ zyEi0spAEaOxZ^X@eCzR=ml4kMLm3*HC!`mh5(;m9$S~GgFJ{euv0s`z zpKw+#YwXtlVrT>AQ+5Br(4G!WHMM@NQka!?ez=xBxe_aVo+p~e~-w$da0 z>(g$rZ>;#ehdqUc`3&t_E#q3Hx1z{T*k54(-l* zrTaA8@^bZEhSKx53MmplG)=QBhmSs%Z*03Bxlq*pIYp!tDrc;gszSYkHgST=T{S&m zKn0_O&VbtYfD&L*1=qr8g~C+rnurki`CqSdZe+M4hoPf%8h#VkNX^_3q!Lm#8TmxW?7UTeisj9)WF=_-x1Bc{H zp%d?TqEHr8)Avu*fQB&)5YcQ2P-+uSfdvINk0U9+D`f|V6qw6Xwar%l;syF=YEFpt6@(IgY7fC2RrKB#m7N*|0v0UorI zmOU_KLf-Rwv}FHc^R5OUNQ+K-Q>bUV zBZ?uIiUuTPwt_DW=>1%P!#8E6=ErpR_JC-{(E@U6*`JfOER$_GRK#76Sg-?*h9Ddl zhKK3^!QI!wIT@XG1i_tR(nbEgAi0=qXhe>*oGyPIXlE66h$@rd&vJQ7DbNL^43g;? zOelfP-rrAQJW67&ojgn zwtH|s0bm*vuL1yQ0=9($m7zkD#y|iQzD7VOa=<<|2+cjXJ1nph0lRfe(C19>7Y`R7ih>sgIBGQKqvp+)F;mo#~9O7N>(w4 z@_mHo4iG7}{EO@$3^CEEG&of;(PSN0L`~#NUX3s>1{YVgoWLnc^acr{xR=C(Xg~ny z_5e^3nmm}DJk*>#GM)TzJ$Y3m*AMR#~$M%1t`0&rhwGDrjbDi=3zgX00n<>sx$>-gs!>_ZNA&;!#) zmi03HBep%T_TWKbZ% zQ(Syz0CJWAJIUiCQKt&2qBLqyU?P&_J1TPWJU@Ir+|nN;V&%pc$tH?&f4>ie7$kLTEHo zcprlhQb70}aPukSX0vndrIs6M7Z2|u-t_TA_B!7LgYwGQ*)uEHoH5953ce;Fw~g15 zY4$V|p>dP=3BO6mEkg<}F%g;p0yjKz_dhsi;7lHSMyk{yDD>cOQ*YUU0X+gDiHi6A zfnO$Inr+fH_t+e=wLJ_1_A#+D1oZm={O0L=zl*>xDt?5E>*Jp#3_w+R*q7xH$6qBD zd!QL?Y#@Ms!-n1E;=2x>qNw8{sG$2S6pevxRYSD|-1!a?Ea0FM0bGO)YJiLEY04eOOPOgh6!NeUIsA6*qBx-{4{{LIEIK~B2y`-yA*UY1v5d# zEd}7XOuV8Drqs|a;&3q9llejoJK}-qut8T-Q5j>%cmgt<4;RmP{6X$i?-aYD01*mY zI3ZQ+8HmIJ_8gR`?J3F7EiZB@zZ+IwIK#$c{~x4BJWw>h=3@+a}&MA%jZm#UF9>}*U`eXY1^ zBjIFk)uNb6GKo03yP6(Yx%^gUv9UU0!SX}7gcP}E*z?vGUGa9X`;TXegPFu%VKq&u zHNXbxy_nEvUDlH@Rwo$EMLGSRR9Z-6305diCfYLO^Jx=ePf#(UNYI^n8>S{E3v%;2OS1moIZDIBKb+`2_l#UfvE9==^ z4op)U&Y~Ms8vLnS#ik35qZ-3KYbIK2GYTr7loXl$? zuGOpu-fmK6ZKyZ3`ZoHClM4)dLpHWmX5NdiAV{jnIM4jS&^o{chRXHP!=wY^vaxy1 z*6*0IcNz+F>*NHRuUnAuDo6Z-cO3lc5URI>8s6eL+o>E5ww&1?T&&^Xja3Z89OlirtS zQRa{C*bTZjRUw4R>&Tv{zpGm}#}n^-XxOm0(QwtZ^NLJ+rElHhTKn=wgQ}j?lZ{S3 zLqkS3eaq`QZP51NZO6}9nT}a?(_xJzaZ#s@uH(Dd=b%~0IW}&SZC}u7FWqwJUFVV7 zW-Yxgf~EM4f_m}IZU+MkihhrrDseqrsL8cQx!p~0L_Vmkr*4K79K^Qor>xG(gEj>< z^&P8RRo#+0v(WdCto0bSyA{nUUUTg=Z|}9IcVi2>zgct>=^d6g3BvweQmcfEuD$uL zeaN*|_nQQnWWt-ap1b1xKKjJM!21@eeWy431OCa-ZVrUC4@ArjT-h9;Neo8n4@SEU z#zqXr-yBTjB|G<%`mf3AbV2&g&D~e4RM@F9pz6}Q*K&W3{($582T7}Jhd=%g*>_4} zsPyJgdHc}VM&?MW?YF>PsKA~^gW1v~w(FO#?^vL_FzQ-=F7!8M+>bIG{oy&`YNR=>cO>=j`*)+e^{o0S4+gsX z`3KS-sE<@@AP*dW*gw&8VX@`n*bUvbYwX#hLOYCYJfVp*Y(Blhj z6Z0Npo}!yx;K1>%BZ^^>qiRPxzs<2{%?H=eyZ$!rUjIc4Z-f8;poRZmp~9xwroU0) zg9i@=1_t z{9FHPpLyfPjjXJ!zc^uPYU8r=v8!=c{|=1(1qrWQx$@UIGb}8OuiO2T z6P`bRo{tJsPMr9Q7XI6nruPZ&e*!~*2Efk$``*|;hnil_&ivTe-$TuQ0myj~5j#6O zJ}`8!u=snc`8O@(8+ZKJ*uT(1Q$8)+_XjQfx5gbG75-c4PFdyurZlz<0s))-0SsYM zu)l_yf2}k{MMeLmH%1g9{x4?u4`BEgD&#Xm5(4_yO7riDCLa~TAb))L`%J!Z$6svn z_nCjw!qNYk7OpuM9pxFuYJPu&{MXo+kizb$Sl`z6T7sOi&1CkdqpK9a=SdiMjxFJEKk+|}J7ri-hzby!G%{{$aqq8j=84e9bD~jqR_j7GF4QdC zj~7yLcT0c5-sLv(X1yOag?PKjRUozTG$CRhyQ*F1*k=ao7Ntn{FfwC43p) zpG{uMqY zeFn^%rVGzL-~BA`oN}45vpvtZ$vphc_H~1^`}Z`LpL5X+PLJt)`*nfwxFK|@>}R(f zC&T_>h(*Gw4?o^8ON^7$)X(59E?eCGoo2hQ@B`ntLpyj@@9nobz0kyujeThU{!oO{ z;`KqVpd7zH;$44XvLD~Ld$e)$;m3U*UnWZ?FMXBWNOQP2J+LFZuc0SyxWbtk`O87U_R!dAs+jSBAjOw|J$&+j(_`51{6`io?~Qm zJ|K9UN)q6m6=6xX%Ejq_xq;;!H@r^)tHvI%ydwzNV|d7fyO-j&NR^Q7yAsGsR2-%V z8{F-?VQlMsZ0?S;lt{TCUx36!Cx9RM)IsXhy`d3>9SnYKY$nxyU;FXbi6sO3ey*j^ zFmm^&5$Uo5pBVA0$3%oy1lMYZl9MYR$jFNBdT*=Y_Oxwjf>~k~8(5dlY#$CYe3teq zRl{|MzI^w3>Cll@4ek1H`R)M4;Tz+EZt0cshF&=;rf)y}K?_69t_XS-*=6@@NNVsx zEHjD%ayIL3wjS7K>Sg#jcUodt5kFPn{}7FHv>Xz+y)x>&W|uu>yhZRQr(W8wIO!Yz z2s|o!dw`f+%87*-*^P@l%Ui+cojSb-b%?tZHfz&N*S$t`XCGuoW~EzyQ$_Cke&-ST zq#b1vV{51bvxdIbaQYD8)0(UF{~$K@AI4pr`Q)8Hj5~g8?8cwQU75|b|IWB8M)ua` zHij?hzbi8>|C1KNbMS5|yE|IW4w3TEeB*AWHs#aTKWX7!ho{{d%BHa)BxxbPQo6o#i=jApbiZf~_QHfioboFI6sFp*}$y2Ghe zJSRYKt~5^Dw{|=^Vow9|8HyM=jtj)x0hXjK0iU%LRiEMp1qR@I*kWsy5=TWAtg2lU5{~LplCt#3+;e-Q_!EeG8f=O zc%xvvm;Wo&=K!{W2M7C6cMDMbwMNITf-F}livfT>6|NdCWVrx{p~h+b?jf5a!9W%H z{_ZJHl<0X_cbBSve3KpRf*ct1Acm_m;Q`*i#5eBLXuFj7#$7U)C&sU6im(e}2tErE z-T)OcsGdl6ql*<>9^So9cx|+9*!)9%5PY*>{?}r2m)nB6$aEmAiWVt(O}kt4w*gu| zgM$CYp&fy$U6-J?NLF~z@jak+l}CHJQE;~Km^$7A+5>Zpg*ryBA%S?17-(z=v_vQQ zsxEK8#5e9H1Fl1TPGISK5IYimZhy*tiH1&7capprrk0Crt%qwz?B2mc08rCY0^5~2 zj;BFn#WVQfG#`{JVuE&0l!eZ9r z^u<2l!jkVxB(Px-hy6XOMm!~dgvLq!UWkeG@D#)H0IjRP(7@5q`%?M~C?)T1vb%Pq z%1r2eSGYmKJ#K-hTdL9Sk=k=to_^b&J_hf`UJo$E@DX{uE>w-1qLwZDRt^d3-(8)# zC1A4~EI@;k82pGk9!Ok1xNqt={_^tTxaw0A)lN`?N0-T9>Jg}8H8JjiQQ+@&NL=6+(e2JB& zZ8VcT!2z0vuS@bj%x}1ZFR8NML|#QNV6D>}Wv|G%763bX`NmzafyCap0G)>({M&1M zXF}Mri;X()K0hqU3+!zOeVv>1d@J1?rY7FL@3M#O{ zeW7C0xPS`?{=f#m%tpH~$=XcJR|aMq91?lJ$1@iFRt?`10PP|}KW{n9PzVPY;Fkf& zpEoYnD~g_`(4rhe;o3?aeWqrnB@i~c~c!giAtsAmwh z#!e#Qn7;ellED5y#sbQcrz`aAwgsH7_$l58Vzmw;~d!0|I>Z>adJP{MZxZk~W0 zreOw|7)TaQHZb8n$n~QQW;g)znu6)J!DfZRkJ6x28;H^vNQiLCh3@>Ciho2EtfpXh zsR6XiSgATPpYP~A#(w~C(&}J=TJj`-)?%VdC?GZq`wYO}2oTssaQY8wnV`+LwjIzsbIS!vhu>VrxZow?gvYo#4Ni*!MJXTL$5_O=>v} z+eX7qGqBk-foE(yG(n&)lz4T)(X4y#>mKlxc!7|d>&IIhkq=~KYVkL@F#sUHn~R)fW_zAy(4JhkT5$3rW+I3=RW$3P z1E>caoE%XwfQ$D9uEjpF<98_BHc_}%Fi%$heP603;4JyBuAy#n175PWp zahrm`(J@@A4dgq)F7_Vm@D}7S1wCRDGIIK6R{;a zZShZSFby`S4juUXiui|b`14HkbG{?T!t|?QQpe&`L=w`qu^cw;Crune6nw7+{oW$x zT8q0|iYtr9bWqXz7m(3RL@*2P#e|tKAUmmGQ4UbBrJ%f)ycVMV67MdqzVmNP{?OEFfhA{(UQasz7zWr_3M zNBF0y%F>Rw6!fGl)e9FUUw+*7h>i5!yS~DcDs^#57jrc6HTQ0YJ~4^OqV)fHDr5avx5-Od$piRA~&M6A<`M!m&sl#ARTWu*nB zgSyoidf8G~^>S|Y+g6iXW`&oA~q5 zs4EM;p*qT}ys%z@m}SivR)(!t{!(Y*Hj1As%e0i6_qf!if2xtl6LcOb6nwWm9d$^y zLd^YV?VYen<#&Rcxsn~`g->ScH1o6;c`o%5fwkIyjx$kf)%(O7P8QS{CK12=lx}kQ zW1Jb+UAbF~_1>Vta--NwyU{qUYHxY@k+wgKJ9j;4vyDbC6`7qC>JvW3>$**lz$)?c zO*@xrk8em8hZS3eZ$S+g+f@jwRy3hOwP$=WPT|5_2&D$34 zU2D5{U4?Kl&tBX@X{}tSIIzwFeb3|-S!-C?KhL4SMNvV$HRfH*mbEI!%zMFxwJPJK z%6j)CQde`aN(N^Szi*{{h%o3;@ZJ)!M56(6w=n<;X?Z?`h`6n>O zTsx-Pw!XG$jB{;I4eyxW=-}{a;i6vWl56Md@XqDD&bMuytFxVa-Ht2X^$+82=M6uz zI6pxn`>M3OuI+i+RWr>K@0y>5vEy7No$cAjE9&FI+jk4HlZU&&5#1s;yT$y=%fm%p z_DVIWILNoCo_;4TIZ^#|yt`zf4Ib5cw|me13NiI|{?Tl)-E%w1@}}D?lp+Kub8RY* z!c|)<6!&g!-S6M5lU&#yF1f@1U~#xTX0p9aqyE~R9!1%{wn#^?L7VtopZjK?heW@Z ze!sU{|2BGQ?EQO^i!oMr*uLVuCnW|f#T3tq6Crjs7XGZqbit4ambE`IQPBMydml?> zz%h3~sQbv(ZI&$QRf4+T;F%fOL;6ken~lDS{mB-kaqkp+b$c0eWd$1#uoaCv|8nhs zKd8Zfr2794>Dl}D@BjbS?dqS^|IZBVFVXJ52G01a)&J_+ZDwWil9G6diM-fYUU>M6 z{~e?Ky;}Vnqm@_ut8T|H_5Tlnv%eTxdg}is+Wp-)i~mQY|6dr|KLOfb^z45?XMESr z+uQr^z!^GPfKSg*7yrF(_cuLr|Hod{!NH+UQMdsB{_^gQVzGRH_8*zELw~q-{7(Ph zV^tGlBmU=~W7UHI@LvI%`d;;a8h3v&w0|+~RQbx?wr&4R_5X`>w}TJ2wEtDQ6ZwOm ziEP=jXg@c|kD1OAhs{V`e<_)pgk^xyAQ(Z6R0YhU*J0~dY? zrPg{IgU{!V?mFcga~~aBG-^>&$uQX7G1EAkSxiy7UMmr_;#2p}RKHE3`CeqX?-O5M zmNV>x($Zj=D6HXUiPe+pD{Db&?SUU|*W1+_wl@h+`Vp1h3qn-?-OJb#PcL+x$fKmOs`@%FYe zP1C@<6Dq8dnRXu^sMz=utNcJ^Meo?cp;nS{eiVo?S>YoZEyz z4YroXUJ^j5^5-zHBN+ zgX=tgRDbZy>~;fKM8*397YW`&`->`PKeVkixxCxSvz&-5^8fkn57!PuW_SO7e9f9C zVn84Ypn?&_k|7Mz-Q1u=o1;9g4nt5D;_EacZGgd#q1CTXJ>o_Q zqsNL7cE_r5z4ehme8ouPVP}R-W5Bu0?S>Y6es~+YZt{ez4ODzE>?~fe+1L%whk1Jp z1OkW;G{ptZ15dXno%!)9yUVhPEqv$9$_!XK^r&$H8f+Mf~(QPI2g$)?x&W$Ty7aHzhP| z-vQCldQN?EZGOYhfAi%aci0K##XlaEeCg&(lByDt zc+HdnRDwj;XmM&I0fg=AJ(3@|G0Y)t2Dsgm{3Je3H@h2wiY`s^94S)Jdhj4-EGam9 zwTQo09TNHpQ;U?gRI+%$r)Qu1_CGVV5z`=DZ~v6lJW{;l;Ay zPuYW(Clh@FV}*Mu!gFeKJ7fyzz6w@3f27UY&huOJAg7nJcmHth2C_L@cK}&B4;PXR zRGBybNSkHK(42td6o1nm^dOga&5{fS;gO|KQ-DtU&s6`vNt^wbR6o2yJ!LQ!f%A&K zn!%)8QOp0=RR6!DXAb>pJ>s%dB;yLK)o5}O)I54~5hu9%r>y^vmcxyt{PU(Yme;#*U5-_0}U zhiB(|{O@&Qs{<~=<`%@hH*Ztk5p-kNjjMF8W$fCHbGKBUzjbj`pX{iFLI@137ukzz~2?ys*qZd3Fqry(pk zV4ef^*Vm73Ta2QvGC*B~>#S%+%LSBcXlL$&qmd~aFN!p?;ZJ^XV^e26i{hPH6{Xe! zEFv;UMo;^czim&t20s3JO1r-$KhXAUvYXV)>?Ykk2`Sg~mbP~78I<2v7m(@i{X|Ab z*7Dn#j6Am)#pB*X?R^@V27a%Sd_?aZoBwpO%|BJ`@zjWyyK0U~?aUB0mQr-EKP%S0=jxr6Q)H9F`$&WzD4tX=VmH=U`! zaZ6J})hk3-nYJU zP1kseTG@Rx=KVV>u%2{p)~ULXn-Jt5ttx)&#TCrz zWMLfQ>{E~l8?w#mmE=iXq1@PTW3A)>h!^xei)Lln{GjDy|EhtMS!uLBw*Vz4SJncH z2Z<|4*IsQXl!_Ly*6I?VhuaVU<@EtrOa8guFRnMYI$}W01_E?b02jk6hf6_~=70ze zI)-baKhl6PWfs7oPOz=_&p!-qB1MB2`XwsGZ1BOGYSK?nP7u>$t|Ey5Xq~R~HV|)5 z>OOccghu3!B?kBxiI=d92pBDf9{c69`LZ{AL2B@D!jcG4(bQ7U%ekoV=j7ekXDS)= zuaP!X-1vH&=3DlQNri|7>^Z~^Xf5o#tT&QJQwg4@GBqp1-MA1ln|hgx(T6{9_Zc3=qQHQa=1>JE--= zZUv&Rdyasf1_g~VqU41tLaM``pY+_SXOb-~@Ub+r3R)J*`)0>nTiA6>dGO%LpSSIR zb86$#V716?AJp--o9wSI_4V&>EO7g@_Q|G=VdhgE!w(;N^a(j<1J$BndT8g~Y$3lJ zupmy8T)22GHKHgDF~w9203xQBK($)ue^SG>;x335z<+Uo=i^Rb&oe6od=(Rf8x#>L zwbL&%C!GNsav#|V(pJQD1jw9`4X}30DRzY;})ag(lIsBu?IlN_hW#90btHSZ36hz0D4;yz*oU+3(&uf z-FmgizSHJ(CqXy?mqH^+vJrlf7(Y&I3oiqcNgzi7xD)Gf%cmlC#wKhSQq`Fx7!y`I zhJVjRz74Xt4q$B!sF_crvyk*$pW`*tDh)OmD-f8*3F)W7KTevT9K$DnB1y6&+Pz|7 z>hZN<_FC?lpvrtTU+cMzaXylcyrj8zw`EDS2`X!WwK@liclrzDGhX zsYRQEE~VX20dxq^95eC?;akb)5vA1krPpewk1Hmqyvb0r>qaiB z?X8Li@x43S?#oxQuUYW|Q$32((YDAHs=9SIuu4I;L}TL!WKd|jW_Fr!e@0Lw@S29S zr^A0y)M~s@e&0z-rIB(8>4&=0-T9)8G@Qo~wDZJ_XIliT;ng0HESB{GG*ZFRSxUw? z;05Ryd9p@;M5}||rKcn>)7Yae8CRdVT`(go9aOekLvlQ*_oCy%kmQK?Ytf=!RsxD~ z0l0c0GIk6{V_Ptk5;C;2F&A>WL$bHW&DaCTTsGoCQOaiMg_YBJ#~$Q+^xs}A0N$!0 z?HAxbDVl>MCpmU@L|~X{^x#XXbWS+dB`5TrN{EqVMEM5 z>XI8HkaPy6IKarV?cU)Le<;)`%vwFC@frV-qJG(|UF;inMATG3z%x>=je3G#ZvHu5 zV%oJt8OB()odM`8C3}XHXH$?E{7Cs<5KK4s)PH8u5wqwO8v3+uxR3!0&dZVm6e>hKybPLLdtc z)WQSe$PW$XR?Q?<$>Y}aF|QM1VMw#3#*dLtN$`1 zAVj~j``KmEY|Zwh$`XP4WFjy^E3jQqGy-;QO{&+esJcmk9kOXWM1keo)Yz*LwNYd< z(FRpNuLB#-Tgo8vy5wR4mYAnP1R8BC1o(sFy<-ps3&I{o<7bz9*wiAM+M;Y}D2o#^ zRj4gtfJWQaZbd0((y*~VNh5+H8=o3%ld1wL?xE=SW@ey*sl_(k#n}Z=I+YrQM%A+& zg#wxlRho?R@+#g*nuHbE&=FtNF1HDS^wnT874^3QV27ypNc5KJApt@9T~F=U4(Za* zcN#GC=3_Ih&uxn}M95$dEULH3f+^5aQJlJx(yYh zOctZzBi0m9;*CH3S`?&Vv&#JMm$Q|U<@KB0BTFFT?7Z)6P2uj_uY1#7%IpgepEz{+ ziKg^-0<*KE=XouH>Xp`k`6dwrsWE&>ZD(a}v!Vu~SeXo_VN*lpU)N7S`+Vc}-iYV9)H`16;&iujyowmM2gOUDKg3>#Za-N%I`*E99 z-#%DSj@<@TDYg!GxFZ= zLF>5P3pp~2ff2jb^)+#{gGZbocDGnBv?#tGvr!no|N8MkPt+J;RACLY$%c1vY)H zT!BN+CBv~-mqn@_ct?kGpU-VE=sPk;f>UtGO!4-;HJ7f*%)TcyaZ%sRST9naUDuU@ zGO+TBOzt=AeQZq4oOn5!bk4weoxZfDkz`~54)t6l|5nuz zrpozwLgsVQjlELEw<@@(7q(JO zFtSaw9Y?n^R%UYr+Q1*s26I!+l?%l8CVKC!)zQrDWV$RoMSb~br;4zY@N?{-_1V{` z&JW0fj_Y zI;+fi?t-unBt+-OH`S*IHCObG5k5PmSO=zj)c@G-^%0Z0U|G9RbnA2c)MvrvFAz`0 ziX538fM(PR%(jl6_xgf1cxhdG=k<`JpQK)z%a$E&}S>{1!{EpXdi&};tQFTy8W&6{2WY~M>I?3B+EG%-JpY|){q$UWcOdYJU}X~s|1}nVW`9l4&Nt4-NQt-ZexUqJ_N`@m zGPa44`#hRc4A#~5OSyFs3O%jbEq)o+I6RNCGEr z7V=(R9aymAKpM^5d(P>c8f$ZunYC$Wo9mx%eI%xZzpB z{2w_0h{~Zx!mv`t*@T6=)>!d9wj#ER#))K=9f8xVxW0swKMgn{X%s}N{2}uQ?#FJk zEa>UY!g0ITmbtsn%onX|C|KQs;v;Im?mT*jto7szdc58{I$11p-|m&7ZN0h5za{Cp zhgJA}lY0u2KMt=t)j8kK%0C^+Xt~-sD921t6`qL}*%g*Zy;nJz>~I?8RC4g6$MvHE zx8-j-)q3?N8Oaa|-@Rxt+UC+ZxhMi0i_6hG^=gxQx609FyY~+_r&pfYWkb`xv?Jmvg`Snsm4WI;mKARu! z6Uy>md^KtzcU8(0tkL;9Q`SMI2y*fAzFn&oSNIK|BWHboD3;}bsRhX<*IVA)4vRK0 z#t43~lVR*&i6c`&nrI7|ejIaC{f>#pJB>e6NwpMVLEAT5T|3p7clNBWQFqMM}d%32|Z{eQ%armiLpcQOz%XkN8$I-d*Y8(# z$fVIS*f!eTBRc=e$%RF&=%97PZcgr}k@3Xjwlb23g3K5dN+v0!s+&4hx65B#KNUr{ zRPUoerPxoRjQ0Ca+8=u`GhquKQ+vHN001p8&6=e-yKJ`W(&48|ikn>gYWlKVD3dH& z$tk}($8QPa!FHxAMe2fP#ADY&rd-gUjC3z`EQXXE`}j-Q>DYV{vk)O6r#7HR@ox%l=Q+5y)GUo6(1INo)i|Lqw-h%8Tc4;>oyt zUZoKeQKXqMpYi^Lj{i-!{w)YI&iFv)X_vtFqshJ_X0Nhd-4Zw$$GQG)E;v270VL|Z zehMd=)@PKz-96yM{c2~3tN*|$nebPLIj7goW;)7C|f$q2(^ z%&7fkZ-hxbMxxsvZ7q>3c=i!Xg*;_^t2xzreB-D>QD*gJmhuUFXXq>0*2|Y#akol; zFp5%;pRKtUZdJYSl!J#X4kV* zw$@JFQsj+S&v_6({qf4R=s5+Qi3H-?)O3WX9K^b;)G#tIY9Qg361h2ZzlLWf z%au3~Cw81#w@`imDZzkrQs}aC>i%lp$E=}MdG(wh zqNkMAwWsFhG>?}Z$}#qgzU?Esv)0)-@T@)Uy<4&3ew~q8ZAg7+t6zJo{W<*>*P7 zLFVeFF)1x)?4n&m;f>(a`_&J&2lQ*^dVBWh><=8X^qoxIb9ozzK4dwc>CIHgM@l_P z7}5EunPG%2-%>DS5pOkl+eiHkQm1=TUH5CE>9x1^_mxx2vx3WCN?=IAz7|GdUo|`= z{oZhN2OPyhs=+@>sTsP4)#l?>LBDdwpn6U{!c(j`6Mrvqn^RBPLN(6=^V;-L*nuAJ z#%-?HrDN7&MoZQQ-k#UsHj$M{AuWEmweEN^T*z0 zZzkU8;{G}p>Dd4LOTTTawCy{c=fn4ZD^K^Z49-Of{NONFcc&n}&BT}_@BBISz3pWF zwG(+>9N{COy*sTeX|UC!i^l7>NC(uCLn@`l@re2E z+dT-~r_UZm{!fwG-0^gkQZo)UaLfEV@lm(Bq(3#$}D*irE(-6(McBCw{Uz zv))LQ(gSd;8nl#hoRIVTV(&Sb_osQ97CIekFU1%*9je>n)*EICFLM2EILs;-9MK%c zs6&aXY~k0Qi@Yk{7VtJ^tx zfTz)?vV*JoD=<+MP48}`lk=4%uGZ}lpYpVBH5^w(=4lPd0Cc}*M7$K82fcRex| z+Z;4_zi~OdA8~VriJ;A&OIxnEZA{z@jp8PBtv?L!{MzZ&YINXSDxp$VoTO&`w&dfn zsbgE8ey>}wOdh-LLn+W-+gd6?f%kp-2nB2B1_o)Aog={a1(g zK0m+L`gA*E8svv;KdiDle3#U$9{Z3VbwF=_gy+31575;W#3hed_pum3O#>lSHoB|`{lSxp%7dScKtk-NXV(-)L)0tXMOxRPF$qGezb8CIyCw$D=v^3vy~$tMIy!6M0>O19A%Lr>oL4AZmgb7JZe4m zs;MEsjWTxy=!71I2>2WT$mqwTvl%)LJwFP&p1YEEx$33IBRJ{%7P&EAN|A&?y8d*e z+G=;SO|%vPra74#C=w$~fL!v3iVlD|GmPk5h!v)1RVl$JAbOu_Pn5Q#frEkJ&0^RW zaz=e);`&}mALD5T?W%`%)H*^dJLXbz>`sw*yjo0%X`CZlAFzq?DUI`q-$x$=ohU_k zXEW53;~nIXTBdPwqR{<%NUdp@thR}+L!bN)NFWUa494yyz(P5(+nZ^QG{i|ZD6$kT zziecp6df#r*iVUfb}*!~`f@dTO{9xAwFQhg2(5NQ9>g*k9Dp#U0$%!v-Bb{DEbfjP z;FBG_#R+5=AN!mV6|fvhTm}cLK>#0G5G95mbX*p>@2_SW4Gho;Fh`Minf15{QKT>d zL7T6aY!H7?KO&m06zixO#eWvUKzy%=RTqihOMn9& zQRg{~Jk@CaH=TafJq?2n!zM1aS$*N)`#pd01Z7hUjAs(W%g* z0L^d=5jtiSx{T2Bpj~Cey{|+B0f6yf3_YH1;eebN85vz2p=(FmEsyHRjb7!(`m!5J zBLo$GAWlGO#PzsN&DfQ>m;)m5j?8Gf=`h;6TiDwo;`CT_bF808oX6w1!0a*1sEwbg z!7m2%EaM@))CvfN9#^9a?X^V?(ymeR@0hbiLTR+s*GX&G6Z2)8=~9}T5=2CV zzEgyMWySD36+&8voN=X{9*d!ffMjf+i0NJI9WqYe%gp#gDHZp#xEuXikCK9Tc%7cs8Qc_^EP--FW5X ztAwoip{z3xtcj_P4MPscR-OqKIA#qR5v51dmcc&Ec-Ud7hlW)XX(HkRGnalkTj$IW zL}${KW(aGLE3`O2RROs{{y~}8OQp{i*FC1Yz9nOQ7&$ouo*|zL=D3p5=Y}PZCUD}uFCm{4Ck>oA%0pnS ze#Jk>_p~S)Cq4cO$C}J9nYf>e*BkgcH-9Mk>8ocm#kva;R&Ng@)tYU@r8f zadsnD`fjYgq$DAqd^!BW`n~&N5=}lJay|3dkE38wOYA3@`|6pVt*&Y>&r8gABtS|5 z;(DZbbHVrg7b;w6{!sj(fJk{3UB2|#BKz1^=G?{n=c)+?*J&_k;>;Uz5?~6TML;6! zbh&k~CIhlp1bP67Ia~_!@`0CG5@H@upnHzNr##~VI0Bu=xQ)c_(YmJg8=SFd#xf!# z-lY<@a4R6{2rI@bfPbC`5fPAmNiELLBi4f%W6!@JGY#|PpI%=_oLWcle#}+N4=zZa zd`W!kxj`}{Fav>3LC0z%jt?A}_m6E-SrD$1D*K7Q~; z)_d7_LQI_CtZXN}^n!L*f=t(J^Vb-TB}Y3DVT$ej0}z85sGZHHr*$fj2*#0vY1t8l;KqL{rX$MiNwQ4Zu`sMo=dkf%U{7c(beILL(d$j02q`g99*@kwLcL=BQf*5xO|YwH=bB9>i_+ z>;Y^<@W_7ZVI+DR7P?@1G3n9jO5V1|(&Lf7o z|4c!Jea$mtyh`Wn01iJZJsn!tdoN}0gq!0aFH9hI!_m=t>!FfsrV9|ep!Jrg9>F@0 zyob&aSI%Bl)OKhgq)Yx4lK+J6BhJ6EAhKw)_3kew@x0!>j{s!=vX**gZuRRg4+gj ztHY?*1~O)jWi3jli`2#9<7r062pMO^zst@ z5u)&8-+TE&%bh8oAKV|jem{=M-}d5G+u)n0Fr$`~ym$E%*T_hKO7iPacW4q1J?NQg zxSr3wD_M89V>FO8FVvpRHUkS7*RJ(Pi`0X&PDxW`o8xwO*#|uG+Gtq5d?$^GnbhA! z^xjo^^8-U=rT&Z(ipyHFcn(vyUTFy0UVFL?xhwZN$Y*#4b{@G_pd$=E1Q>{tWH8ZT zQ_-UN>k5FaUhmahojBCwqPU18cXO>-q8t7m`7*U#f0F5vHr%tBWN{hFhCw)6gWvz2 zN)o2u+O7^IgB^#_QRT$wj>s^=oe&=KTQz@Tt)FQ7-aWtlkI8qr-5R9oR@ZOdmK6E< zGgclJ8Ep|qQrh|40Vh6`B(f5~0sVk0B5}h!Q7SuUo-$}_7#2+njlo9VGmF5tz(7+G zVOdByh1JLfFRfe4wjb$qCM%fp6YM7|SnKRg&q~*~b{%0eWeQFy?oFY?QH6#Gg#~Ev z+8R~;9wH8iR74KS1rZ)(fno}X4*?MSeyA_}AmHsr%;DzIs>{PK-#^bU+Q}!u7xu~) z4*q8Nk4OamJ>3(R`kA^$3UDVfo!hG;oDuBFHFw!C^UYi!6%a~M33a{6YbOzbqyJ%gN;;82FU&9b(5Ky)D90E_D1hQA zTjSU9dS=(BB}dZhSDT!|!VPvxL%F zuxxe?>{0C#C^=o1-`e!}`aEfkC-iUTm!Cg>*tgW^yLqHPH3UbWL+c-Y)ycO-96uXo z^;TUQ4P~(jDztc?XW63zE&ApV1Yq7jXN$FQTOy*eiXt%7NY7(HeZ=E0$D;t-!+veyJd#aC+lfh=uGs(oy0 zNwl!G*od*qaJ_J@SKE>B6W>OCos2HkBia}tZ(5hk*@OYJtT4J*#|I*Fq9e3a(KgZI z1f^rqlBB1}Uoyl^$^@JPR=<5MpoPqcm7k7VGmB)(`A0mdsI1&5`8D@IG;_+shWA-v zD98EQUsuB|(5 zY%D~|0_jnA?q8R6B|T5Pf9q+UxAMjIEZJa-x?PP(Yr;751?Ln{%%5+se$!R6y%F)) zt9w0?Iu=tsVNq5awC!6~qYb*zexp#-G2G`RU0U~U1S3g&xuO4Bh!l0O@X;M+7LYEX zM&E4fv*bYN5{J*=Rn~$&o^!#rsrAb`_273$AFA)h3%v^V`w;zLA+E^jOt2Of^Lppi z(LNe=F_Hh%?dLT{@^h2t)`D2TV&9W}d?$o&=4}q$guFgC$v*x%ca*rK(rgMB-AlT_ z3fLjY_Hp@0joZGKSR2+Z9`m!i{{!qB^nkui{)=Q`LAGG@ zo_r+e(DA*uSmTGu(MF&=^&ob;Nm^J3e!_4c)8Pc3DFS&}K!#_}NH4XnUniVVs>s>8 zUy$vM8K1@uRH->Rg$6+6MEB1!s#>d{J6$3L(fn2_c&!C&3ZJWZ{4%;kenz%I0K5QF z4_ORPAYi#`4!O>C-Rd+}aEwz!6)-&B(UxTFg{mw#*?%ZUYM=Iqy>W74Q7)hlJuC!p zFLtWWW8Ze8Qj;F-FKf0R4lpy13g+lB^0V~g&Oh){`Aa?4I`0e~fV(YnovllT=ggBZ zTF4Om)`|#mTG!$+vyfFio+-VHN9UYtMpsH!qucdYAg(3ehI)VzbA7zKpRs3-4IiZUw30~=B+GJlQ#RZhG7y%|UfAroy_IZB3f-4ik=0EU4CJ9*;ULl7By)uY zQ6Mr(*~rIYZ=WEu&|RLA+&Y2}Xv#o=)}tC5U<}9?xlHDwgHFhVpeKb-wR{1xspehT z=ere3r3!RXij8c4$#~#in8~dq3#M7f0`8XgQKc=hnZaBUm8gdEeu>Y=eFFlb?DNdz zdczrAr#ez~g*Np?hGWCT`GHm`UFwYs6Fp_0iUaRedmfM1(vO70CEbZiGi^w)O2Km; zz?O0tCBfeZFAgO1C@N8`Urw-Ue&vTB^r5@*EEAM`*KJ|K|U zKHx429^KA8Caw6kY7?Pu< z^`5K;dF7~j^bY5|O%J!(cSb@Tk`P;kt5h3f)}6T$9}-`Qf=rl3xH}>unc+^omm$);}N?!Wyg<&s%=x8sAdJ6Z!kYzX0mSo zPWwzSoxzYvrylR-1x6= zB5-1-s2GT(7(F!$^g*-q=U2U8jj?T0#_EnlN%8>lfPx=Ye&N3)^A~Sgmju`%FgaHn z8^LfovLR0c*uDN{W9~kifklO1KPg6zabKaG!N=y-<$Xu1FMVP76hIBRsiFhdRScP| zkU9Y|JYu`@S$*(lX%F?L5d^NK?!EZh%$T3&LQqH=f6~jBB9_ZiG(gGy6xd31EO5jD zT8K{)92s)k`73tf*Otuaz2$ISvRqfdMg0#YH{~$2K{d>W=?PeJiMJ;C$Me~pq>Jz` zKh9Byf3=!C6cn?UJMW;QI!n242615Bfa8DN)CwNQs;kezi~%2zN$wP^9m_(rq<3B@ zeT}-z_qvaN9HT+;o$5vr<~>7!1l{&XlGs1A(ha?acMJJ{NJI*$kkrRCgr(SAC_Q9)(=dn(o#0i%bG`I4cQ0s-pYfJc=q8!yFKT9W0GfVn@kl@0S;(8H2N}J>F zVya4~N;^Qirb9ghC|#*@Ue4lP%IDOxG7+u|_{I#7)u|Lukv(4|y|;9=eH7QhA$c1{ z-%lk9nx%ssG^N(QC{~&(?Kyt;>TL`vvM%XR*L$zL4p2jAs8uqn8^kEtKty7rc;G~p zYN7@KC*H5Ah^A==4l3W)1*AvJn2m9tbTtT-*tCI^EBCS|gJ7KqGx_c?qZkO-9 zo~j03K%4_lx5K$r$MfJ@FTOhc);-<&sLW1~bRmkGxLqxXwVM~N>L$k?>M6(e+|#%6 zpPO^1AzUviwOLxpcNvDhPJ@?gijNAfNpFQWS85c2fY=FF?k6BzOpQi05Q2Ec*%D2oQaiI0R`Ya$G0neu&j`OEqB3+B zfjIaX50^#c^IXwbduB%N-DAobc$KY)^uP*h(F!|UhUIIsUniQP$=R7@VwQvoyIH^u z?PP==@o%|UUaeTh9?S{P_r=Hz;%Jk1T46cs5&Gn@Vx;3IOTvW{BEP>#fn23-y@$Ou zKw&L{%gzXi8);OmEZZOz?CC!Eg&0Iqc)CZpyeccyZa>>2u|Yd}dMvGl!K>^~FkBQvmG@~4(wmJ+ zRra`P8^0k;lcuan`itlbeu;)z3Db>|6u}daSan%T&iUqJYR?m~tU3zCLiXyb`3t&@ zRaqF0qLh5jG0^2m;Wv!p+9j1y);alfgW&2;b;$@vlz2B|Vuwk8Md?hz7RBA%zFTMO z6^Bmk_nEAdYd#E&^?Cvb=Mb&ZAFOt?B*?dOrYcOSztaeGvUYV69=}#IZYMF}Rx{!KU5HU=ltTw; zHX2`mQJVr<9b4tVYi4RCJ~vBztn5$+;H^Sy9OE~_o#2=)Yj%@qX^ZQckJ;zWL4j*D z3YhOiah#y!H234{U+8APm|R~t2Yo+18|isH^Xi2=s?_c7Utedmy&W+(lXrCi^&PoA z)0MK@&kJgkA9y=*b*d8XJkleG!Dl4gayHHneRsla9`{U_-h8wIkgF!jhThm-HP|hh z+&+$?UE^MLiU!PflxNtqbJvY})W!?d*-Or|N9sa{HEI?Gc5QwP#MFg3*4g_%r7-rP z;z5e(CEezi$|;wev+vrs@LX0A_rVab`Oj9oHJrz$o;SoTP;Bd{hJTD5c zzCc0p>PVfvUVd+7G}{{I+Zt~0w%+jjmsFP)$2n-308Q=P#sd zXrqTtlGrDEx2RN7x2FEJ){547tzx80DDzIHAk_h@paUoYz8iS5wdk|9?$cghVtBm6 zj?92A+>Ke^Z1HpmeV{YUaPyaxR2pHo5g`IN(eyCZqW_~!AFDYwsy${rcN(+1H%rfv zySfL`uQA6iwkGBmPuPnODJzZ?X3s2@m(+5)NO!Jp2(#^VmCJ64p-|LWPol5?F3mGK z_%n-(ks|>jLiZ;1M+#-dw=K{Btjqjr&w_+JmiyJXm_Q^?Nms;sOTNbu47b1=6?Uc4 z4wp^)<>P3B+eAX#lFpTf(`OMlyFru$>ILnqP8{M8wymcwIgSc{`c&oh!=>piiiJzJ zfKAm=+)ls4~ne9o@tlx^I*q<5rKCeG>^HYXGAKgxh3LYL`C@G@;Up_x&Ov zP7Z2&`$5=%cEAhgF###U53MH-bhQhL=L3SQf3--yaK;E~xM?wN7l{0jF{-LJ&3$rB zxmU04u9nOqOQ6uT`+Ya=4PEE#HHErrAqi{|g*SU;@d>ip?_W5&xJn@R@hyB@fj`av z1h8bj=ms`BzH_}P9eFN`p=wmvzL;9%^fJYnGa9>~2{rZO2PD>-thzGkdVDU3?+})I zvV(sD_!g8%cp4}z9Z2zNc9i+X$D_sGLX`2m<9X|MYJc0axs@#cWCc5O95N%9ZqCG0=c;O`p({r6=}zE8Z7 z59xau@=?CT-AzM7{+&+uhsW|^2QS0AVjg|D|L~i9_yKn)n?i*8P`HQ!k?B5BUBT<3 zLZoR+2TDH5K4?^5A^L8MvW)^M?6A^9ft;iOU{r|7Z#f|=#MUYJmMg@)ZMof|5dX2o zxnCjSON-rotWWYD?ZjszNf;5#>-Jg;&uCqnLV0u_i|$Oc-gSl+#6(OOB&{6%DH4BpINs; zyaqivT%|r-`K@AsI+@$H3*UlQGMmI|b>+j9iYIlk*e*Od;sW;Ugq^6#)|4#YR#q29 zTi?aOr6s|&jIXDths+D!nS`AXVeV{IFWai#DpmKjRew~fnQW{1qE!2>t@ejf-9cL& zRjD3!M!qOFu)S*FRc;h{)%d*aYO-H(q#Mk#i%f$n7XVk}Drr?OzCr+J=0|?C_usC{f%u2P~_R&lCzt4UCHU|AIBfXwVQk~9xJ)N&QlfTUA zqN$1jiPOg-DH;k{QW{_YmfWQ>t3i<0=fM({(}@=xCh>wefdY_9H4P#*hEq~gxd|jC z%CpF+wnU=ic}E>yU^`tDd6VV-s!um`^`{MH3dB*56D-%{q{c9VBS=rB01F*TowPa+Hfa(6AsZ$Baayu@F${X0aDg8Sd+GEVmMM>`kZL84$Luk^blKWMQwg=Y7~c|w)TVlVg5;ul6zRQ$mBjYhXlZmOJu zjO*>Yi?K9LKtqMz`7Y;3gl^y=&C@pl*8!4&i0h3mQtz4lh03QFmp`OrgoLMPVdP;Y zEIDebxpIKEK$fMNM{Sn~Z^Ky_=WiaG%Q3}qX0EC{*#ff2L$jTMoCMERXZ2)a%J7AN z&B;Xrhs@qTemmdtDw}92LJwcR_T4b*|McjZ&b*F72}kqk)Q#ld&kd?iLzk9#A0bbk z@jglf7~*K2Yq%u?<~Wd@^oG)IDUskqC=;S#LjvHtp|=+Pup3}r2EYKnMUoJERQ^IV z&SK=5EiT5lm%~eC0LVu02eO;n4x<1ZoEzq4(9x7GJ;984iz3MlDQAe@*Z|HTiz68y z9k!b6D4{Yoy#%qUrS%$0;ktec&ahyKE!1rhTY@@9UcXm@k3=p;;g9h&0HyEUS4`8} zIhsBw|5T9?)Qm(uip^!$Tr3`b9!nL^E z&KAoA)x_(o+1Y~;mKK78;rU^=echdWB4j9H&Ugz;<;E$KyiZ7vqS_WtaZJ%oLMB3aje<8=lHiGHts8T$Fh zTehd#__ITALRQ%J17Oi>p_v;X&9W32*A*KdJ+O9JHi^rkyp-%k!85&HK+YbCaDZ2^ ztjT1|t-l+X?m`StXM#0p$^U%*+P#qnKk~keQ47IO!wT?}fEPC}QNMBc?@jTM)V6wi zBLmx01W3G$>)-O7R3>K*est7L?pPdkc|MopFTrAS~12PF7fsy>&c%=#XyUaNvi&6akL95Z*D29UpXJe z-53|PrNKXa*jJ$!q|R%S5{sb&Rq&kEEt79w(`~{sw?6L{R`VrYm04!*&;E-0Wtu*>!~KQUjBotIk{C1s z+o_ps`rQM9sZa}UjmI%y+$N8cA$g@C{< z*4TG@6ku_OPus)+=Zaj&dM;ij@?*`|R!J*!S;ZI!_@|Bczr3D;|6gm@|4r)Y@9#eY zum7!G_q~1lf2iWMwzmH7QqRAco}Y<{|CW0Gt9JdLOiz7%{eMb5{|2w0J$qJKT3S+4 za#qFrPpRi$()E+v+}xa;ob2rE|C4qd_aE9dIWjUbDl#G>B0N0&|EtvF;o;%#?(X)l zB;Fa*bB0_yIyyQyIGiQ%V1fV7!u31b8~@4l*xK6uH>sx+3tI#LY5@RC3kxqK@_$J^ z|El8sSE=XU&h>wldi4G!_54rH^;r^6N=oYAMvv$v(f=uoCnzZR- z!SQ(P=47Dsz>`Y;`J!lX3UsP1sBbAmhePAy*Kp^PPXn5Wrk_c4ATjJmbuJ{hTfNni z?K2J-Ibx`==XoWL6Z-!5+?jTL*2WWLM$el}0FhJY*Q@!5B3%6)nJ$(3{A9XRLR&(S zpr&6oys&ukDHfpTv700bso61=VuJLq;3Q83Oz?=4dx?<{hP@<}=VZS)g(=z<#~7E# z9;?~zasf_uV%{b35E_QvB>5FUTt4jE$sdQ-(RI)fPyw zs+!=Cx*syKCly-wGYLeKAa6#qSIyFig8)VxvpoK#T{pG~KXy8$UIF8KPC#_{_|rhV z>WnDP47x8^jO4q+`k9vQOyt=Np^hylLl0)tfOva6Y+hbBXG~PCYK4Trg9Wq!z0CsQ$sw=f2icfyLY*yod_Fqo}dkn7kLQs4k zbf02)vpKFMnbbX+K zXe$cgui8!f;F$=!F>;)xez!;bC%s+{>%OemS2v=kuE+qKPSVI)q?~u=U!cEWAH!%M z3VRxaljRsZ-6?So$E4FDr=h6gDT2p+kvLu}Ny|QH3l=y%fF4+O1zqVxi6r~>OQ0!* z&pB4O{6YG=Gc)zbj ziQ1qN!s_|O92zXdd^(td76@2ZLNdNco*dcT!(B~?y6Hl?Ec&;L`xO#$Ay5thM%IN% z#up;88 >pVVkp6Rp>aeiaPoNtGTwA6GBf}*$p&x$A{Lb4nmfnDID`h;r?N+RwT z2%J-L{1gdTASkvMap-aBaIKKuvgho^yBig2B|}q&D|Qon;svPtoosIb!eM^zig^wc zWS*XMi7)^Mbr1FWH8{?+>kGP#cE@{}Iw;BoG!!7qRS0oh z=pB4=NN_vrAtBw%WS;52zio4-U7vY9F9+UxKm3`yfOz(g*W;J-^U0dgGo{Ia4}onz z|7qjNuyn!i$n;~i4*TGAom5!Y(a(GULpcs+FdXqedOgva@%+tFl|;*RI0R3SQKn!Y ztQ zOyVG%MbW0BG(zYsi)?;XK8qiCs8k>4*Dt_9EZ@MF$BsAVj90s;R@qD*4>dLZs_~I1 zy|H}O#$)!Y4Lob(eIif3KK@nrXY+ys%y8-zZF4=@c&mr8>a30T_-g#4vo_w1qJE3B zHs04n*ULlGALiYjKRs*XF@a`Aa(*`%i%HzJ8k#9Aza}P>9PW9`@be6H=FIDPU*mm$ z==1#X@0XM_uZOhxnYSSPcFp^(J1G`4@k$40UXM3^B-!@sDOyVUP!~fUn%jPO=Jhbt z1%(A?^IEb!A5t|4bVbhmdV0{fE*l%Hs{G}^K<#jtb5|8Rr~JRMd#^sn`m<8xYFvS8`AHX#GYRt_gvK~nx^u3_TGN-*|T3> z-sQu!p38Yh?zf`X9+Zd8-{bkyo{WQy4@X1`6tYIF*~=-7gt#_3^2`|;Tz2CMb7w1g z-Po_Aws$2?R9E@h*)F8G65r!Q*GiV<@T3L&jb{NAyD5)N)sHhbY`8#XFrhxWl35v|#ea^S{+m8&~BIjJK$VrziNn@lB)--q`D zBP%2&hl$wE1v&ijG^(NO5ARm#rD3TFI%o0|EDM=<`E)m45&N=stXZyk(vcqL0-S); z(wMeh`4~LI^-YPFtS6x6TW33)dMk_$wr5@*3C6;U3Sg>Qz{uiE*)M;#58fv5`9z!% zJ4bq;`*Jhp0Pzqkqx#E_Vru?{XJPhW_r4`23!u{3^{jW~E^w`ZUs|!P%!Rv(+NnU= z?^Eb!;#IoeP0YM|oL}zd83$jXt4|0~)dFZ?wN;mPX?dsqW|+T~Q*XTatLoMYYH&Ew zJmvggs1!e^W_ib@P^ql}UG3j7-KQ3{J4qZyU{GLIFI7E#5gMJF3VLvGpn6!VpPdP2 zIB8+O+obeX`$-pfRo3IpT*RNhzrWblN&aK&=+x64oM|`&(A)cZg}Y~J!NZHU&=Qik z8o%4{!bhaD`}k*r{@5T)Auz~Cw2uOv=+jkp1)JajTMn>gr*K$dcodkZvk2S#m#w2m zp*tF8Ok8+GE&=?eKuyExhnmh`bVo|}>*_0@p$iQ04rtB-7}I5hhXXNM3z52m4j*Qa zunwF&2%~{U*Nm!OBA_8YkU9#}CIv2OrWZ#+n2x9(xJ25)Sq;l|?^`oB0uV-vz)*r; zhXb@7t?NQzB8;LreYjYyNv0_zKk5pZ4MlTO&-45lq>;h|E7o;PQ#S5kaC~-N*BY4& z*Dbb25t12+EoeF)#(az}O)_K94jTHBEHp)S%5r#_bsh>}B!XCh8Z;qV^ffzZ$#0<^ z%&}ne*xM!X%p;H&Xx2A4`pA9QVm(2(Fu+2K^kNPDj;u2WN4>y$nn{IE7VFL)08M~F zJn-1~{)E=EfwdsvCiEq*r3Wh#c01@2*!8n_|HWMgIE^IwF#cUaBMKM^4tnEe zaMSRR)0PAPdlH*Yic17w*#U0u2tBFS4%VXU?ndv3g!LUJ8A&BeN2b#4Le6L%GZZ4* zTJIi`=`ah;LRN66M#O^(Qzg68;NkQZ5LR;y4Po~bp~499{zT>nsXE!#Y97ey`|740 z@VOn;NN}Xa8d|G7q3$5)^jk)y1$<>e!*m3&xd4lajI!yEGMLWzKAz5(3iw*jYL)^$ zS^&oENBj0;y#~S@*rUT@gdKO7G{LN0J9O!mWKusm#yasB&*yG zQ$A5I_YnPbDl-k58Ks>KC=mPuXH6<#=(X0X!^D|L#Z}N`18_P0nmJ@FBMiXGG|YI} zT)$HKqb8butwoB>wq5kD5mej790|E!V@}M)4RoT#G~`(@X%v0E6@kQ z(N5IokjIjlvP1SC zJZ*TE_t`N?wgSxzV5)tfk3B*QC>DesJr2LlPurSowg~-A2zV@$M*9#gFIHH1y)f-p z`mN!V`3i)#yS}n^k#=}Gzl|sK*veE4A+?TH-C+`SH^5B=8aHGpDn9wGSgfQ|@(Km& zLa{!TWEj0>aC;qn15>R2ttjbhT7p@InG|p@IsI8lrU@SjZ$>lh+Rh~u$O_4Gu(@yN5jDRX+%kZI*J0e06>h8|UTV-^F4tE1{CXMrU#w4wAc5QNU4||B#ksgQ^jWgINhT>X(%ir)IZioAA*M zWAiX+6_2r%XKlPdO}wLFd9z*OJMxh^^leZQXf5lg4R z0(_cNdy-R?Es5G)NBL;*I?Nd5ZGN;}#+t|GY@#f7KlQgrXlYCMYSSm`St*MnrJ^&sW?S}-2O9ap9F z8OgMPMj3G87U)DploLBpjrGWBgHqP@rddAP@!=Aqh70YNFESf8{Iz+mUWHWUtTe=; zcs9^{2Aq03usLE=L$YPA)uUayESJUth7EKemdWeYc~k+&+^6<$C9P#WSkVw=|ED4g zi;~ERxIpIAKab2Cu1AbCp$&xZIxro7L(@nyEEk_|9(;L&vxTh#tj38_Rf@b|!yfmU za~;e0kpkaaY-WjlD##2N!pfUDf~gCj3jXJ;n=hZ{qELh?M^2RK4BGr5=d(W$>tPxj z3Zk<<$N2!jY}L4z(Rfqmb(C*}c?#VS;Q3t2i_1eVbg1F9MQ2LRVyQ8(tl75>%tzDc zgjDH6jpo`<7`pvb#^h5<%u;~Acc3my)vpX8ukWDEu$5+5)ZJKeY}OksMdb2Av6G1L z$e-rS@dTT}Qj>7ljzcJ4(W^)FZw!HL4i``{Gch&&m^=uyv(b1Et^3;>WhKTL7~$RG(<1kh;X5W~2~W!LJ3 z>0j_%dpp052&Q8#bo8EIe9OAoVYb_q&(V!stTF~x#{*foM`-D=^h;(;6ASRtYdyR4 z4mP&e-jxRg^T+j3Uccz*I2nAUI*WE|r*)^EAjdY)lLq|B^so5%={{ong*%k4XLCEf zt8=l%#I*M_j?^0M)@Hc&e2VKaY3(yEtbY3w{Sf5e24bO)|%k~Gdu7cm6qX+m!z$MBDz6FRHLy}WBZdn*tvHPqTip{I>UrIGpS2* z^_;mU)s{GriYI6DS= zJrw^q?J@iUPxsDYKxhPbQ~+%q0iPH^-rKUTd$x2SipRw}TFAp0;lN)$FHA;YTe#E= z6!0ZoO*U?*&3B~e4ijTL8mBZoLEUngLAc9%p#y?nKA&Vrv*a{LuH_x#z9`WyYt-(k z|B35nk)km=Q(4h01wuuFn(?4DgOT|Za8VnG)$xr{_#1wjkN(Hp&AHm9K>7{`&c-KI zS(MQk$MHe~5UVdGKAYlbJUqEIA~Q3l*+4f)8Df2@!n7R z(QywaWp6r$e0R^tLk)NGneD%~r={K&j%BE{B%ns$p~n#XqYN)+ zQ4eSsQ7|MUnS!~)U3p?Wb{c}(L=^5$ey&uVn861(AD|B!wPNsJie|v>owG>buo2%d zZ|Wk8(E>}yBeg?xGlf1LIJ2B9j5@7Yx`|TO9ycx=!6eS7*UTr!ekGy^<|DR_^%yzE zN~T0%ABIZ5N2ubejMC5CxcQOKi@>k6tVA3mZ9S%mp;GAS_>DYN*ATkr##ioICk;kJ zeLdo}H8h-xV`QwrxH48=DLAjhh_ZW)cKFNf^UlHgX600)m&zEf@6TfE*RbQ`Bb0UU%c5NdYk|)ei za`yEY1CymHnt4<2%4f#i!0pdhZMG16F_8?c(UOdoAsENgilo}sqt{=A3VV$@daHTX zq@urhr;&w5;^WjF?Ic4{s%1{*Pd9W|cQ+HO4Iws`G`UKo3(S49i#xW_6`7MUgO3V@g?7Z(E&4?M#~d(glJE?$EtZ^rao9 z8x#z!`b9ZY^rJWEun()uU$#^2Uq8ExhSoze%Nb*RX7wB3^Je?R!b5?geItA3v|9As z&*jpjy$aK}9bsrb0DR%Bz$*!*S3|qSJmyY1sMtHw4Bs#)+;|iATc`PVdQ&8fIt*!Y z5F#z4Y68R7f;JsLo^SrR`Ms)q^2fn-l@mieO@t&PwVvM5?3<8pR)+84a_T9AR5##1 zy&h4Ys~XV^+-i{uI~{LfCy8&NBdR`OU1!3s(7lK<+EA4=_ZyAE-Ol6!vJ24!kt@SzQ7IIy^d8cP%E`l*;(z z*m}=p5H4WFlZ|~>8@2>apsW$*c;107L0E0tZZnTv@w7WSD0HC$Se%(@s}4-(FKOCq zP5q5q`FO4q^u1(gsfhIj7{P7$rrPFszigx;*wPn1r*3l-p=FzvMBIRv%YSbPZ3;0n zMp@b&eiL#TRcrk4E8zD)LPA4j90n7VhVGrb(gpqf!B1{P@FU)s#~wHxRn(_&6cBf}gp?rd7f$PFpDHdwkp zzKNN+_#E1tlyBXnKwrpt+MuD-BDYwfmr|BqRbu||0a@;|&!_L1nv_H1ZtBBBU1GQ% z-#@4hA&m$w6c{y7=04f|5Q&i#$O>!Q?IIHS2ciLDRP&*|LS`3-CUafhC>aZV?!UkU zx{%J%GR38%GYD#HbCdn=;q$$BGH1m-tlF{Di@vveW0$W%Hq%-8F&IaYe5+c?blm;D ztc#z>1`aQ*os+cXuDeq4petjQMgycUCyaZ~>*I$~z3k34yS-fZ#n;}S3F|2nHXln_ zg#7t#V-p-tM|6@H06xn+vP=x;N1|ouoGrqrdFX_&(4BS7yqPQdz~B>%CQ9-v(CwY{ z$lps8Mesukj_20Z`!|zDB7Qj&J%dW}f~~{d3fJ`zgIZ(_6I!>Vi96F}_o=9Wx2F?c z04U}(1q8)^$HC&xSvz_!`)j)$pU=+i%}Q{lo{Bjs<=oRyD0-$l!%_SxBBEIkojBF( z!59A>j8mtiJUhq2A#iZ@USZjd(%M2sENBDqVL&!+8%n!FKAacaY`YpdcUz zYo;+wicXeULE2mRlsGGmF&0ht45O@PBzu3ob5#P`GIH*5iYIorJNtB!Bz?&S?!}|% zOkMxiQqezI1Q=dhGqV*zABCjr&ARC7Y8mt;35zfAT`kwv33MT|X_atf@Ad1H)u!f& zlOf8T-SSEuD!BwcQDDJ9v5!TDkgpIVTYf;6QCi4S#`L`MfWiFqUPj`{%B5S1YWC49 zDJ@#YEVuzf({n#FvtnGqq}DozSZb}rV}-Bmmn-_0uKvuvd9tc&U6zI(^-G)Y?nlZm zM(Rj^5*|T(6CIh>d&fSU6X74nY|={Wx;K&+n0relW$j%M^M}|2t~L9>AOn57-F$Pw zavU4`$X%1P95h484I>X8Bbg>LQHqoC1! zKHo7bW0v#TQ5SdOq`uCmpW*FA=f=x*wQpNwv{{zPjh8!Gi*W#BMx{*Lip$s6Oj~2l zIY|sv*+cGF_b6R!d^}!#OMCM=yYr`Lt;R%i)qW#Lgwa^LWekpcpy)}P)tlerbzuwy@PCu!? zOiKFYd3$qpqU%~f)1R$d2=gkNnb>#rHLNwa^CHgeKfNZx48(tsEDQUq@*LXY{ znqH7&^FOO_nLPV6dZqVq#M=PxKw`JetigRH)vt?wH%o8sNpCmLl?poL`du9p%?zKC zxEoS&*>|M!pGG zzUb09%Q7lGEqt_~n={_-CihbD{n5^@6t?l}#mQ-YA-Uc7ILp=I6-@|_BT#+8lSQqi zi*pPaRnQ4}2J81|4~+J|;UvC%Epb|;MAk?DWGjUg-X@~A7D1o56X&UbyW0EEzvQYH zD`IGD)bB4`?onl`@%@rdM73D(m~XUp(uMIVX!FB&S3am%J?wI?XfTc_03?ZH;dt_( zBu$~~DfIJd-Ba>hH*uQ#yM+(||T4fqRaA#uYXoA@r8 zWx4xruI#xwznK}`thqQw)mdbC=;Mqo=y>^tm62KH&a3PfsW14FbiYNhD1K%P`}Q_h zx|>+J0`V5@7T}liOHFH+M%Nw2CCuIp5Q&`QUvKUXPK~fPVjp~3h8Vn}<`nvzYoNjJ zezYckgkM26??%6lZ2Fu1(){)rWs(wrBhi=8d?FP!reCH_Ll-)$iDbW>{Gs^iLfjSZ zqD>AbXH}ZS5Tu5d6K`;s)%MTXr}UeTuAGH>M~E-gRk!JXD9*jUQPuQph5e`=|7GCs zL9FTA*7|8ys`6=y)=C#c>@Ah$q0=C%8;_(>lQA=w_QL(Gi#-t$!K=@e?|0B2Iv*L* zq9zs*0t%wPD(}{6EAmn;Kbo#?|3(bJJ5!ka0L$n4bWeA^7WaFW=V!z3{*AF$-%8zg z;Ly2$ImcHb`?GR>bK)0OWbVX9N;%f*grF-O7*7BD<=emS4o*MF^PaBNZQd^;!Nm?y zNpdnGTcI#+dSIslm}1pq6SL?v4>&k02QCi!XK))t0H2VV$Rwx(g_s54 z#Nd8>QauJepD#wRrYR=-z|Jo3W2Yewmkz!BY&VYl3g;VnStWRfE`5$yt3187EMX-48A+{}QoE?wb1nlgH% z%7G}Y;j>UA2$~EIOg@_>gWs?QDY`(E4x|07BTaw=rF2SKWn2EAEa^eE6l`QjIT7cd zOydC4!~rw~VKS0H^%fEu0022e>$!)ck&s)MILV!833#}K=o!6BfFfb$*1!u3aquRn znjYL-g=`@MM=U@&C3|H(H6hg?zZPJ4e^fv}k-483Oo);Z4cEq!AZNW1+5(vDIyk@q zjIO7-uSX1*)cHYFqZ{ig>*$K65bk0~`dX@hZp1|eQqT?r=Mx@&2-Cs99jw6sBl013wu z0uRCAXAliQ3jiQGBFQH8(RO@M=70eSOVu6CP61*LZ4;a=3u=>2px$}2t_Kj191Io( zg&&fnFmO!@1b~SQb|>|F!a^ND&_h^Ive5%L3?LbK14CvjFf8Zl3C|h~4V5+D?yY0i@E!XYO-A$egC9~ z9*|x`M~WaKy(IJ|QWTL6A|OSOCQV5oQ~^PdB8UNzCMZoh8hWqNL`o2lVhc7v!R);A zU2~4PzHjdDWbZY`x^tX^WQ-(F{?C2?E;P@00uk;5Ah7L-K;!YP=<#bf9SuCe4`bfP zj_ij5hDbOY#o`MAU_@1Y5yPX%qpMJ0651EdKh~tA7v~xu-I92Clo&;!y*0+R?6A<< zxOq)XP2*6vDi9hD+UHNw8;oytoEUvQB6h*>Zrw;iU<2Lq%K-`|GY=Ak8C`$^51}|E z)kLEYaAvWjQpe#*&7=z1q-k~}iz}Y%Y-|iUc5m=}%}0DF@f^9NZCz zMWJG;`rIr^xI`5NJf~FLool!o0F0wH*4ulyTo%cO!yAUfAMLPk;PAF2*dx{?J{mG3 zjGXl_fE|ItC{qIdGXM-QFeV6VO+sN7?8og{qf+xDW*(Y_3{J@ybV5iV!ixg&gy3Sl z<1S|;`ed*)d?(z5`q@p7mnepNWl2|2HiiB?KN$a2;;z^||-HMkAA zU+BX_Q^QayCa_5%7~o&Q3*kr-S)PGu@psb8np9@XHn5$atwsFc4!zG|EuKuR&EkDh z9fCGYKw9+gR5dC-^{hK_^PKF?8564-zHkA$h!^+3eh4g(%tsneNP^uYU!Yd3Ze8E-?LI1nGcxeHpLySnu8+hW&jR<|5m{bp_N5AMk<(K{K_W1Egrx0c$> z!4jzDDS>4%l1}&i#X2p=y#~jSWXq7f%lFZ=|HL@<7QDzL*qRh~oQ$JR3OGqm5^m9_ zn7PJ^5%FRQ%M}k7b47`4rycMd`M-OTY+G_gl9ve>96b`xbpR5h#Gd&J&>~XLluN>`EBK^1kJ^Nw zK_-uDi2*pc``|wS32vyCUAzl-!qq%@;5LJUCC}Q9)4}~!R%Mo7TFZ#G)k-<;t<8m} zPcAq1A+aNg_DQyHPb@tRkM~KU&F_G_8^gV}8JKZEp;l5T5q^mqZnq6#5Qf>eJVZ&X zN#(qgR$WW4A+?SzHux?FS1t+#!m+-Isz5q(huc%`c&dXXG=d!OqMBfIkaFK3$=?pD z-x+__4o>rGJo4~7+_*8k`$@RR$(Mv*Klt1IQNx{5dN~~RS^%a3frTWzc(L|8l))&Y z$xi`~B__(K5@HrO_s=@7ayWTQao(~-*plGEd4!8ap#Egs4SJ7r#8`3SrhVC_DRKof zM<;!1Lr!~RR(y!_wj1RziHjSK%}UhtW@`?F_+})!stytg(sjcVG*mf5!(;c;R&6lx zHj^-?1*lCP;ezw##jrT(rhAu|JimqXnE;$@_ z+IKThfO;STtC7GP$RJNlRI~&cVGaN_0`$u!dbcc%S|<;U)!f3&VK}?dx}t*kJMD7VpNRKX>kj`L;;ZMdqxwtz2_kImIbq zf6I2c@MjX+0!*?2QP%Lu$CaLm<~6-Mk%UDiIQup#o}v>}eR`8-s2#i?DDp||-+tcY z6EpZR2G|Mu{PExkINO3{Dt)yX{wa3_-emR4w(f2afB7UpIl!7Y6 z%2Nn2XsE|QBDDOv(>NU>m+=#)GhK|_+N|vNgcbCVZ|+;)%!uVUZ;wb!gR3iO2$^68 z13+YWxwGHespNh`&f8Ks)aXEHEt(KB8I)ig_i`{XrXu0xq@SPb)x7j;a7j1eReF)T z6gsaIWM1q+s65jI#U;VNS1v>=b0vKnrApF$l&a@8+ak%NB?r z3e1NBGXt?PNpUJ)7$Of6MnaOnr8sUUyf8X7W*efdjBM=>KAa6^iwpclz77Y4tZ@Vs zScDWNxart|shXdpMh>5NwkgyHY0h#9VK#-_JO*GDf#&b=^#t;)q zuH5GqA5Oqsd(G*goBlxz?8vq9LNK|h>ADV; z;pBp(nQKH`hNJM>e#_UJjgPhOhQkcx!cDK=0a_3y#xU0dm@AOrrV4j6PVhk^B8@r2 zk%((j2~OehR)J96K}eEC`8^ho>{rP9cUMi54hJZ;EU(|W5BT2hH*1u?XRulb7DQ%F zB!(=&J&_6acCho71PlqHf{v3@h~>A#GiTtgru#no@@v|^B6-g9q+p1~4V8yUZ*F`3 zcD4Hb?&!i*BPLITKnqtA#1(hCpD{e=8hVwGCAb`syXvBon|J2!fXi*3sE>M*UR9Q;h%noj&PCi$tY`1ZTiKg(ZkZ=8=Yc=V!~`sbi4bUXL<;K`_m6}O){ z1+l7)YifQmfG3>;!|cH{ANk+B9;DDw6ngJ(ucw3CZQx$UeI+K@%hT3_0<7xwemg7@?J*UOe(n2V?BNx@Kg(ysKgY2eGtV?CMoceGmfH+4smhk64mw;PDC{l$_D*w* z_xT@6l!^5FTc$2w{%CnkbjpW)vD5jwb5FMqBG00;=0SZiQ-p)@=FMDJ9OKG7=Qc<| z6Ie}Eh2uGNX98@uP1dsi%ikMbpks+r>s4 zp51qJKu4;UBuN=wD9JG39kO(l`MPaM$Ekj}k)>+eyoQneV>f%N85SW%)zc3;e3EG$ z{vMil;i||9rhvnR^>D=X%kQzy-D>4{_pgRqmR8kCn-A{(I4lycSmW_Bh~rgvzo&S$ zexsPTPwd3w+f9}4OTpGBEfeF0-$<1Yz2V`^f9O6#aNW2Vc@@8XpZ#QELCUWx-_l4= zx~H`wrR60;MZ;yuDI6gcPn+l+@>AR{TFF$m=vMj0w7=Y!c-Y0PQR9-F@C5pT70PRS zVl0xOlt|(9{7LH$K*(ZqIhF;-Zx?Uk|lx$mJ)%k!=Ya!qDT z;a|^7GRcYovhTbzf}l2bopciDcCP*Ly8%HrT_Qd-s)XK(IaDDF^a1BIuBe9KRhm$) zA?tUq+fl=UEeR;G!;YVap_y=2;d(e-C;$6@a z_ut+Q{f@LT4X{ZA3w7wTH-4QEMjCGnXlWBxI=)ScayBo8xai1GFXitrPaWSsyuGnc z)`9ja5948}>_o0Nc^JyVmS*eKFXEJ^D@U4TbY?RFXAU*!zYuL&XOybF|3uM&zGvKZ z3dD#Cst!o!pA1hIeW(t`kbvo7xYkeGfqMUiMZ9QDmCADx}Wb#Oq+I_^z;tmT6(L>6a z5Hy`#d;4eo?-UT-IlfgGXe7kbD=px;%0&%JJQP%3zGLT23&-gmt#fb$nt;>S7~!RR zqM~b}5~8YI*?CiEvIaW-I+C# z3oLmFx!ycaGTG>~6>3F!&vMiA{9#S7lSYW;Hf|nSb`OajPUkvzmG(CuqvU|-=&bDT7DfI|k zb=|b&M=`nQohQ<}l^c8WC|vW2FAAxb96C^Lgj^P7=GuGT1D=FO@Izn$l}5t+ysSw+ zPfFULCk(r0J5OAO@NX)>1@e%SB310dC+zxk*fN2qq%|Si?UU9~5$Au)&MJGbi=@0q zL%FI!0w*sb!Ggq#%+Q%)?ZJMvM)G~2C6=Gh*oS)lN+i*UNk3?YPCv~&1$AcOaWQf& zE;YQ$8cbdj?4)2ErAcXy)yy^Ei%;=I>iWBO04)7h^_6Q085~FJP`lY(NK4fvybqD{ zh!SV9&PIsd?y61n-!-g$b3gilB;z5*RS)AMBbKzzr%xUc{0f4;RyrIM2{v*JN zdjwnZPQK(P>k8K#pIjM46S*hRTX7&N*IN9!mbd~YCtwc6a<#%$S=@C%Qdib}Cf&Tu z7wZwfCyuv1iesg3N#p+Grp{CD*Q;Al*<#_>$Zsbq;Am_ixp+fUWPN1NS!Qo2J5?UE z&?QI$Kq0&o#w)no;qLl+!%V;D{0t0`2C@;F5hK7o31Rgt<9wizc(t~U$JP))sHWBm zsvKRx-PAslhJR09`Sd2>*5_;xS(<^dMG~l%GD0x>Kh->AKc=t5i^RFzRVVIiotW%D zrTg@n#SLC{ur>;BH4`6lK@tppoUG2HDWwlW$V0aYA&ZcT9cyOBF)Sy1) z=+O9-@3_@y-2^tAl*p^hC`1J>mGE)8{w$94H@-$qUks!Nc*$LioJ3>DdU$+O*RlAG z^{l1RnXkoYg_IaocaTASx6TGSKy%8$>?dno4AYZW~Vjw1S6Uo`?%IhK@PowBT5 z76sH7M7g=vr$GtAOws3;^f?}l^}(`ld~-x|QfZ#9G-8%8V`L+u3+#au`#R&d2io zonW|>Y!UZls>e~@2dS@-*GSAlb#FZxwgwGZR5!s9vfZBoTz-9i;QXcBCU3*Q6eseh zj(#C1g^9WlyL#hPc$o!t<((E6+pJM8?nF z2@Hg@c)ugv@h4o9J7=>Z_p7xPnSnkXk-hV7Kgfc(7Ol^qyE>ajhIOjSM|dApS||?W z5>7T^&0u-7bNnN4Rik&$xqHk8bcqHGogTOZ?-sse z{rr*or}@>*hgL^cMyL?lsTvM4f0xcAmU?l3YS90=#^}o%0}utPP42!7yNh0cFe?$! zr-k4b1&3keWOKCrwwd+@XfZw=1VGM8O$m#Q=wO{E26H^%_7^NtfT=k}1Io{kad07fMmk z)ojG6Kk3p5=@MF;K(pOL<`|;nIA`*OuS?++6?!O7tbhz%bplD0*-b3g`ec8fjeoZp z6Su^>1bR}BXhjzE0z_e9Mapyhr1Y#<$qG~Guz-CZ&yn6M1smoCJ@k_M=M52{BF8bq z&6C_EPtsEtBOp4!nn^wAibdTc_lq=m#V%ESwo3=etN1lTQBm~bO!1}fcz*V7B|#`i ziVBe<0c@!~d!J@9F(f5u&oNIXFsQ5Qfl=G-EYRmcJz#h&$ByP#{3wO#6DIFuwikiKDf z1v_`8uh0&RGbt%GeJ7eHHt|*A1d--KFfW<4NO zdRP5Mm(F(a6$vNkwk19sVB7|2kN`$*3(etf27bKi(iOkZ_aW?)pvu=GgL)tDO9Xy4 zkQ_|n1CbCUux2Vm*!!`rxrbvopk9hPL(>@o-2y6`gNVCw4rZ-h`E-BOC$y_ z#*6f3s^@pWQSZGxNnVaboCb;QOy8)2e(7z_3MYz} zV>Vu~GV8TtDPDUU?^7O;cS8Mi7I%x@DNIE|2`sihUib6`Ub=CeaBvdsUy-gsV!r_s zF`KoEbS8T|xnC;9v?8h(Z-qY(w1Bj@d$NZr?lK#s^usQv>A_Q|Ot9K+9dx(nAE~T* z+Nl;>6>>NII|hKxGRygzg=VGq6W3uBMljWq&aE;}{bX8qBJ49~t2c0p(!-WkSrA0X z={Ep<>{hm%ueIw^ZJa9jd@?!vWOM~r6y1o(*=fp7X2GZpcx%N3GiMP1Raj$ify350Mi!7>~I=F)bQW)50u*Fr?3G!ta0`cBS6dw_yeL z@XecC%6%7*?F;*-kJ6FFJP$HGa9+ot;M*Unoj*9)@s{yWhgb=5{)d;GR-SaO$h>_2 z^yO#Y_#=RqeHT;z!O4=OT*{lm4+QshU$wn-(fvt}wrsCqb+3hNpRFu=SSe`*hLV~} z&dAl81Q~s`jibm6DIX(ra^A?u;DT7ypcs1h^(tZ z+xIVv6Gd|~CfJQD4^Oqtk1xizcfE~qv`fHBTZ`8eTgnB<)i?o#Mi(FOR@>dl&!1)E zH@4=PTQm@+-JGyZgl6d8?GnBp|H&XtF7v*>BVlRqB7*sXp1NvDS=Xn+1Apr&f5!}9 z%*5XVi4h3r$*bWd=a{Vj%qI88PYF9+cg4w)^5uR~YnHw)zE7~*=r@@AQRT}HQYApt z6yL6oJ8bRxwFD(EitE+qB!B?0&S)%V*kM=N>3rMrR)62h$yi?;Nj}wn@U#7A>({%# zE`8~bU$^r03IFr1z&rsz~P_e&m|lhZC7;popi2Z zK2H0{I<5MD>VtfAcxB)WdSnb2GIa%$bdoqq+ynBFz%MyJM_I?7OWaNn7M&lvTZYJ%9pv-IKw1|g4CR&sGlVB6XR*R z+X$=FJkyP@0=29Wo2j^~h};cjS$*s7!9Nxwa8t*N(B;V=LY!11K0afYU*hyY*|7wa z1rhNlG>A1H|y>$F~TP8sV65m$cgUNpsi)t~N z3f*QyQhiZadqTSVHKN}hg{a6;! z(lf#^Flg`h$}-X7|qauxf9P7HL{mAVrrCJJT_#%*JFu9dJFM$Zw)Pfi>L$- zo6l|NI^uhYCoSKG{LuYQS_^RjVzrFrbhH@&4g`I5?Z*q|WPNS%hI&Ec(5?QaCOnm&Wd9Li+ z9G2#NRn5AoO;^A3c9Z|A@^u@e-@s4riKc)v!2#5!!1G~&EX_BB9{3402XUoDr5OM$yrvbGz`*rmgNrk1xgyB$GSp~uVJD|=9k ztsv?6EnmE1i#UQHTsiY;lfoaVJt%K|@La8+xwYVxTH!!z;e^`5`PPT4YDHVEMPJk& z?YBOnsu2-w#N3FBfpw|4O}MdMxO;031jvm##HQByo>zZzsqKl2dYM;SS%7-^&9?Fw z^@_x{il<>0d+S_GbKsaBNy_RymBXwvb+#rrB!)z6SG$xJQM1)nwA%J;|JTEBZO;+E z3nA^bTu}ul+Uq1W9*9O2?f221C{<0q`&JOmco=bB)xB0F+E=6LH*EPjMro!Su2hS~ z0IJd5^x=4oCF;QoA=T>8C>KACj*0yao50QhLhSG$me8UZ2(flJ=v;+0xBqTGq1g|M zCh&IX2?Ij1CyNw1dS27@z8dbmY1$V&+;_gUKR|QfX2(E`=3t^`SR4NApq|2v>_Y%A z6W)Um(gzN@RC@K~J~m~NyA*2URBL0e^3e1vUA4v@=?bCTTC8Gqk2(OE`f)UY&?;I0 z9a1_bAf1!J$)yhM(`LuT5g@H>JiRJdJx?JI-6a$#iG<(;O7%EfFfx`s5WZyD>@NBa zl8i@>&gocX6qX5ylgABl*kS4N0Q5``*P_cwAIw4s-2$#<~ zAN9{e7=%Kj)kAt-O_+>8FhDc}LSu9W_5S1}!;X5cV=-D3Ir^ixi@8H;g`f}Z+8=vN zAQ(N?jqZ2zFR>lBKl0HD71FN!v;p8%z5q!pyHm0;wmAAFO;vou-FwPgrZ9t~Q_IJC zq<7gXj&z?66b;gGFoZ@#CSQw@vx^V&)mjb1I@6+g0K@_Uk+v8;9iZ z;rN}Ed6tsH#A`R|#2M2+{63N@VGb2wVXww(zDRSR_F)xC{! z0)_j`=GE&xgBTpe;RCr!hSNCw8Soi{I&{c}p+oal+sD)8h%#q6yOCE>&D6d2OT9`y zvkg2f4Br=30@u^x#CfG~1rOI#>N{HFObwPlS z|Jd_b{JsoPU@!I%tte%M$8!&PCh^`rg!PtzK~yk-6TCKn1gstF`nVc?F&J@N4#_kk z(oQuJ1ig6%VueE4g9arHf<*ZuW4l1ZWrPDGGdYdSahAZ1%07b3)y1F@MYySJX7JKw zafqT@N-u9@Z{?;TFyrz1oGSk7=?Uf4jjU3uj^e}uD?{Vpa~PQa%#@LE+J$M8lQlEb zW~aw4ygsM)Y3B8LEYrmqD-*fd85^r}7iTYC_Me@-|4!^0o|2>z3{x@N<5+VX#6Pdgs&t8o?1h}tGD&7nG;|9mSFmra`_ZjYbjNt#7 z(aOs<_vSqlf3y_gQ4H>l`c|jfm!< zpY{$5)@n~oPC1R7<+Vl&%4K>>LFHESs7_mN^8>VJ&o=e;?0095`-2nj9nu6ue)}z< zhl1U25BG+sA&}4}0wS~^YRjoGG3?MNFR}4Zl5KNj!X@UM!%$j!q;HqTZe0NG_My=! zLHD$nkdx7kZ)sl7wv@bgGAm%L-(oCDO5AvdqjN<65#iQlWxfVpqmAei1OUX$bB9?O z@}Tn|7OJj~XKYM`80F~+Xb+sQ9|r4^f3QTb21fFIL^J6ukTySMB%k9?Wo^8Wl8~Wm zW`r(*3yA2kEY=FY3x3DdweZ}B#w8=WNNRtqnBe56w|M-LI5P(g62ecXhBjU?XD${$ zqq)IoFAe2$QGKSY2u)|I6h>-($ul-c5JUW^hv|cH3~vX41cT9ctW5d6e5Y<|`uh62ckkBL*2rY?>gwvs%F6Qc^3u}M+qZ8Q7Z=~Wd9$#v zFh4&(H#avsJ3BKo^ZNDc>FMdIsj11y$%%=H@$vDov9Y>^I_mH+P0$$~9UU1N86F<~ z+tlgr@Bf#k)78~QB9UIbdiC<<%g)Zu_V#vaRTZ_el3G~!iiYa6v@|z2H#IfU$Q){J zE;T3TZ&rt9>MUhuQlp~&H&(~Tr@p?vuCDICm^u{|6*N}oaoOY2(o&kKQ(Rn3BoZGz zdi3z&!@|P<%<5!irro`JH$6Q)EiLWNKTVy)#Kff7SQ@PJA6cEq$jFF@h?}$(78V*B z8WIu`92^`J6cp~`6Brm65D;+v`gK1)KVM&8A0MB8Cw6GQj=Q`2-^30}90Py@kT?Ic zvh&EA$5YEpP!G9kC&I1hlhuoo12r1leRcGIM~_Q|2B1KpbkKLpinIT&D5cRIsgOk zx2Z!1gZ<0Yq3wHu&=&Zw1)+&LAP^k*Yayw?HzdDtEwL*Oc|zK8u(r4-5hZF`Xk1s) zcZd6o&l2|y4m|(}to{{t{-J^r2tbJ`4CHGDJ+)@y9+UyVhtrq0Md^zfs)&2dFdlyJ6bfo4#yB4|Fqm3W6=N5LM{a35O%^ z4aM1_$KFIRcVIo41)Ch)=;x@P&%Nw8{I>nttni7MD}`ogcNmO2;aTvy%x{yS-~e}JcPAk*|~6^-gdNCAtTX+ zX2a;b4-6H+j=P<36{P!!cD~B{zG6LH^QRqaEHuInrDC*GJga}|!ncWgKhWSVjA4*ZIT-SukA{*FM?4@kB_|p^eY6_O!Vi$$cDB1zcYgc0%w8-gN zVcr>*x$bc3Z6aaZV8c__@ItKCvJ#5Nxanv;0VBoP=zb@hlig4QY;wkg1rD;`t|-m% z@v#cufR$pSj%{=cU0f4AEFP_|P58Sy7jw3Kpjkn&q6nAL|B{m7Kf+=^5^s z+8>S>_P=hpD!z4HnaRnS45tO^M-hBoiHQnzAb z4~AVY`S9fx;A`yZsVKYC-=N;|jfFKqI1G<*RQkEl3GO5Hfgo0v=LD5g?pz_E6J-@6 zKG9`=vHE&8WbocZwaBP8g>B=a;8yiJGaX8{K^<uI?>OD>`;_teMYw#> zlMWPDTXyh-S|{NW3KXI#dS2~mg~Ev(@Kqv0ere{!xXE0kx!<&3^QWe%x6?oO-qJvw zo2_0?Uf4PWuTnqluj1~QWMP!g60$J9h-U}yQdK^O2UKdGI^4*(Ptib~-0Qz~D$1Yz+O2N>{Od#Qz^UIK8|Sb8{?xMd?Dyx6{m;L@kPz}mlwPg? z8mJ@r{OIeb%9o>WlScB#-)Alb9RFDGdVc(K>E@T?eR87wpM#CufIo-Z<lEz*1_LNxe zQ6gMru!}j85{G6iMj9D+vpt{?q|A%yFAa8cwo&5W-dVz`_Ns8_3>eS$^bAb~OYwb$ zCqmp{J=8+4>Opp8mJB0PKB zMVJZK?8#GH2sXph54JqYjYU2Z?K1XTtZsTJ32-9n`!qu`MaEhlqh;I;@kA@pZ0?O6 zk3ltcw%+u+eau zu6N>dsBF7D_bE%aOH2;Lnf@eOIPmA2Cklxsqwc0(ayJ-CPa8=lEr|!^7e$FHm0!!S zv!;PMA#1!1{|nUln0&J55bM_4Xa2H5TNwcSk+>bFge`2#&IsM4;dnLF-+Nvt$;t9hSPmc?#Eb|_8WW?T&@z|uh^yA%N zgSCD|nTB*Rcy}(@V=qLx#y38!YX0S~(3quzoo~?JmmYP@NXf~4JT^CFZ+N9_{e(G1&yqSJH?aDe?@}(*Co0`8N{Q;oT$Yd@)T~m-Tq`Gw zYa9+)rq^een{P@x91h!!*XJ~kZk~!d9C2lC$Qv+!uUK$6>TS{RV1D$ya{D25EHJ&H zaLas4{q5m+_;^Fn{^*wW@52ckb0ZOPZd;e{*JP4KV+q&TwxPza=)_x%yFbNuOsQu= zay*?%6vuWfqJF&|vL|G^G45IyJQ$Zxqg3+EZ(MYFcIDYmerES$HL=&~!8x5THX5sZ zr%%_+lbD-m8-Qg|M-aGvM2=977~=lXXd2> z;25Wfe?VkbQy&6$F%k_27A(`DxKgHpGPVxNMOUuqmU8(Ys8h9UJe2?o)s^9o7jEJ! zi*q3TWG!eqfvF5&ce-TJ0*W#!=>mwrSe?NmswIU8c z)Agfi*KSED9O&qDk{AjcK_r-O6P&1CI9CMpGYRf7e+s<@p^_z=Rq(lJ7QamV*v|m8 zn_pcy=qCmgFo>KsWGJ;vlvib)HbiWa{XUnoeL?`ffy^wHxRqLjYje!;eoT7ajcd95 zSTb`HTqfrLLdEbDsD?O@U|$1c>bX*SR8ltk;jhsCu;!E+B%9h+?DGQx8Vl;gz)zvT zE-2<4g^&##T!Mo5O#}nAz-uytHVTX-Bl!Wq2Ve!A;icHS9& z)1IlOTY=b+R0ZS^k@*XX2}cC<_Tg;`Ec3VoemnXN1(sP1-JwL}uqDeDijj8uV8oJT zxHh!jC@N#0(`-5w$dEIuPXhwsR5VH#!?=rPd5uA`WrR)7-E%>+IM&_^XoW2xA&h92 zL6t1&u9UOavJ|<3TS4(Ih&$*m*wY(X04g2V>fck&H{8TB=$#jl0TsWLJc(vmo6k#; z%xl?`Wyd68_GE<=lE9?=iu?yvtq-c-Ja~5az!DCCNC3A2Sbh>>N``r%=yo%d@4dG( zIaBZ=AJI}-5Qsy>P9k%N^vx*7VFjjD67z8&%4tV3zs$qvo2(+51$mlfBams_lChnN zW_W_4OCTYFYvBZ<+!BT9_8!Z%jO1E6iHUpA3M_gaVE!=4LbYVvKmxZZ%y)3~V?;zZ zg~gS^BBAie<*O`B#JNntrI8sk0o+~6qsUt3E0%OrG$NbAVn$(cSAd*R0CM`>j9=4c zry*$PkDihdUvbwEYfvS1df#TTZ?()bWH_~!?g5c5UjdSD>lni7p?)S0K!L0?5Ox?A z@E*%|4D%v|o=%wFR+|1<2I4sl9U?>RYU#9oJ=T#f&B@^nowE3Xe@I+|KFmNoqp&%puDk3QOLv#|O1c?!O*q z(N`frzJ+)w`_%o#z^Xjn>LlLsl$0kAem&m9Jbm%2vZy~Wu=r^~G4jOJ{Ug_M`YGr+ z5?u*U9#uuRO{~^wqbs(&rXR^wqF#a8t2jDj`Q`eUdU!jAh&(1S)>2ruDK#%lpWIC- zi4v}e!d5}{D$f6+@t}0cXr}jQ2D7h^?%rUYtz}uoF`C6b$E3hoQcy?|g``eJA5)O|8j{)?s=64N@F8M(*5?#eW(z}QBje*(}Eh=?Fp zNKk?3L=b!y)e`3*ko1&xJPwL+g-F(dSTMjH87bR^Rw7?piAGzgLt9x?TSY-zReM|Y z+qP%F+iLmR>owXN9on0s+FL%DsOGeHjHqi*x^~_XZsqKFzvkA5jP(zElp@g@VqN-<@QthVC8I%N?s{8|{2wZGHaOt7V40Y{y>s zY<6nh*XzimtZQ93SIuij;Z+x;@Wy-h+cuqh8YI80j-a|uUwF;vZYH`fP86aHbGn4jbn+i{wYy!(J1uYs>z0V__IoX;n9`k(g|4BPJNmmLS=9lV z9zQ)0#iK_(m0jdWPvfWuld7SZ(9W1!haFY5@MyOx5GC=o!wW^%KqR9M_ELB|YE+b> z(H9|XV!zZ^)=kf+(RTS`U!bt~MRVyR>9!pQsY|lW@6Gy+gu4Qd)P8CV+$i=5tM1sl zKVUZ1IiPzjn(-xsbC7VPiE|t@nChvfwss{kzO0xft@m6>lVv|!{eV+bF+AzPd42_d zKbQN_+LKjok2IwwG=}trNqy7oWqw|d&82R440E#fQ%lTi9Y;1;`SmPiZZ) zx9UTei?x1tb=%-a(JP~EVn<`3GlQS`C;0KhUmYi;3dh>&dYjC~ews@eElvOeli)F) zl%vie^f+V;wN*F?&m1W%?nX!V=S`WNHYa_E=BXK-jVCYgS9cbhs-DSMs1E~T?OXcwdOpW<~(oBc|V-< z>74Uhp1XcL7bq|vq%|MnG#_?rKK$W)}(~!M4t|Aqsa#H2Ts@_#~rPeoM z@AYW7yGqf&)na?yC?L^%PEGY#16l34BkS-=PJ*DNR_rLPUn4vgKd|LyFeE22)+wrf zyp(RUR2sD8?136~63mlWcIjT$E_%0o_ry|8*-T->+qAjqtSi0sAH_e6X~bpd7u!tv z0ha=DU54Q=DgdTQv%Mcmt@6;M<<7na|K6h9)2r`Vylu{bNV7PMx!$jfj3$;R&0Wk z`Dfj>OV{>3UY@%}HYy~8orZnSjmxm3{xZ;M$u|4{WU}4d-2DHm+WtF({_n~5e@WgwvhCG@|m?UR3E=zmw+qDMvlL$$q^nepGNZ3=-9pAi3Fs_m^?x1yq= z{_eG5|LC=U$J+n7)Y33?TB+6Z!_XQn5cHoLEzL=%HCkt9XIiFpaB#T%&qlie0Idvw zyM;v}Gu?#?Gzi`LzXw`VQ`7&qMr+K(L~FEKT3Y`x)1EnV=0BENX=!O%td)|I`j5R< znHFsSk!+=*P!3s+|B`IExc+Lk|DJ65P^f<~=q$|4OiWCSjEoEn4D|H$v}6nZXR@XB zS`Y&CUl{bido9gCN6>=pKa%Z9y8kiRTHV*k#8@) zp#=9}Ko^=F<4(+ZucxWLU$BfCWC|&Eh_swu*E2qPoo>P(L^IW=kl!KV%fyWlo%1Cx zN0%CIheZE-l#(vkHd1NJJ&V zaCoHH4NGb*T>KunTqtJl5J9}JNS{sO%rq87DIgpT9#;-ZJpEV?%RJ0!K!n<5NM>i$ zIR;NKu`h?@J{#6m%tm=H*Ny&_Y`1yEKVf)kZPLNzPnzs~XXIw!;uUFpK5a)oKgdUX z5SWGO0gV|rR{`X=37)U4%6FN;`9$t3%k+&n{zH5}y*PIF_m=^5V(MEd1DLsGq+3na zh*b0FHx~5Qv4KTfr&}Cz_nQ_^j7mKX)Js0g&fWfeP@l_R$)Tn3s-n0QOCwBk7Vn7c_7`0mTcRfToR@w+h>RWNVfI=bFy_)PW!($*(zxA zZmF;vwK{d6os--C5>vfI7+yXm1`)z`LmnFDQH1DT|&PrO88W! zX4rw#bfA7;tleJ9+R$2t<4t{q2dt;g^Bc3vSwB6~mMP*eW6ZaD(5mF~ELBqU{^xBw zp38)7k+ZVzHs%Hgba~mL@T#REJ>Lcl)bB+>qDsXiD_ga|S2RRg)F-lM6NfG@e$5g6D01rN(1^3W{JobS9Yo{kh9y2f z%j&(rCwp^$$V2^Gej#X_qEAON(1UYEIy_%N={o#;{xZ-_WqM4;@k$Ma4Aq;KRRjx_ z*b=!j{ktMGBgd7`ZFv#MB!^=y%V(isZ@Ot98Yiqi$c> z>8C#J1f#h+nG9qeJdO(b{&>)4OT`O0eeXeI6h`x;w2gH0?Wzz04~Mb2OPlIFK@A)>N2oXpwJQP-Kt1n`4Dp7l! zGxyeoTc^I_+A~XT+qMokJ-X&4bMC+m|8!bBN#y`a~XcYf$ss+`h;i4&;qH`zyS{FG{L5U2jqubaoXFx=`u01WEHXdWVB< z?(y0LmC-fksDmCfb6t{=`8&3PgI+0%8&mM7?>O5J`pT}HPW3Wh=iNWouRLCtesgqP z@b|$0M&fjOocV?b-(_7rPUCxbM>ixiT9wUi*MBLI-IR988n*psvW*b7rp-L7m3 zOm&ih#;++yW!ci-@GX-^ico42$m$QNqW-8SkaH^DhfyRy#$$Avw~i#*g1s9!Q!>qw z$ys)`24%nKZUyw73wYVONCs`j`0(+(kUp0)(5K{Nfr z7~a3GSEB<^_y^bIjqLSFVNF-Ygz1j1AZ=ey@OcW~^@+whR9Pa_ompe?)oVQ8a0x9^ z__!;hkGUPG3eDIixeT3ysJF3Lf;{uMu=qCZ*6xiS^_0yZW;F*i4j4$P?Mk$45#_V5 zCCMxmr}7=}1Fwz2;vvOJxt!e>=8A~@i?F zhK`jI#Bx%_dfJ?GQi0aaHqxst=k+FOK4{dM$59Q+j|6jA1 zeYNlVu4S}HNJB(OqavY>r3I-bl`YlS*BBLwma*@$XKyUoX$T3`(59${R6@ctIlCNO- zcC@53(OtPavAaU$jZcG$C zGRjY|a#QTC5d{&E@Zk|D?XA4ND!#b$M zc0T=hg^r&W3aI6%#|lCL5~7Vmc+bHFFac-~g3nQqr(k(hLO2ajUpNDpp`GQ4u#gz+ z=3^j>O;sb^GeCkVJFI6}jMT|!vdNp9^CCpOEG)siV@$*a_oPok5bK$ZBEF}1i)oO|nF1bYptnSMr{6Wmm(!J{$Avjz2Og2e z5Ku?m3n`n)A^uXnZ-ff`SCDOqL~7aQ)QbJ78p8?@IzVDUlsHgb3fzJtz~o9+NvO&+ z15^gwfr9X$qJ6o@P!{Sk1ye-BHqdZ=&iF|-VS!Gf)*Qk5Y#8I~c*0zW(^SH9Fc;0l zma{Nv06J106-Yy#q$A3m36pI6AP*M{#pLh4aj@)oEPy}7BW!|PU0tFnV~lGfp{f|z zOKkN>E)G~!8M8wTu#mhGL^vD&>=RLy#gY!jHEx_}-6E)b zVe43=n^g2o4*EJ3olD2lcw+qY^75QXb!_z|dLDc>>#9ZG zWy!ocF7Y={bW(|EgabOdmgIU^BG;Kr&BK?yC4T4LT%08?l@M>zF<0sNNzS>)x(W(3 zoo}9ki$Si|F)>~Fg=r}{R~NHEON55L#m3M8qHlyLB97S$*>i)R_Hph z1HfM8VaZ)sMGSC?PbZ2{5qt(@AqOc_m+em}6dF)S$PwT>BlWoWD4xJ1%T8tzq0_HU zodcIvTM{yk7&=K!(3*^##HdcK(dGBd$0fKM zn>LS2JgjToy-IBTjC|sKr#&|$#8x$G-MD{nX6@UO zx>IVl^|DiEQV;d&atbA|b5r1EWt^&;Rqf86&h4k#uJSr2wzZ}o?g|TT<_EJ&?ssMO z2$gxMf3U2rT-Bj?MY!>BSFS-fdq&?!x+k-|v(<|n6xgFr?keBR?y486aawcRDK#)~ zjs9|v)U5T}nBMX6-lz3CmzI0=(pqz+`Z6vTP1chgZ}iQK_q|Bysc>v@+1*=G*Q*C@ z>OI%{-f2x=pbHwWlA&UT~zH9B1|KDk$6J%`%VqjBWn z-H+X?+a8ub?^=JPYqh~9{%6tyP9U;9PF8LhhL>_qyc?d29jISLT9kg|2~yjJM}bcsUHJBh zAu|%ZWhC^#Ncj1Y$eSb44I{BnM&iDWFl8QJ-tzcr!`6M59!&tli936a+#J|bG}LCr z5qvkS_ip(3yFQzS$N3GTg-=F}mN~8KIp4gL%FoN9oW?c=j~$2Qbd+xka#g+Pw5z0k z=reBL{Vfkt){h2X{>{aeZMj8u?ZmjV;**2MPogr$gPO-59x&aUeq=cQiORF{O2 z#-1KO6+V1@{rG0@LCws^n|2RgTi>In_^ck*I(5@vzYI0!xNP3L(SJdN&D| zRPEhUWMfCb%>i@~S@oeibb@<&X2|KAQl9}i0650m+4Hq`RAEi0ZA1U<17zek?i#NN zbl>Er`raeK6Oh%zlnc+<=ek3-JX-aO(b9f0+S~tIt#)PxtQi0QrPWr9R)AXVPp9@@ zMk?9tpIYs|MYBIgDt~d=Ur_ez4=6iw@gm>Xmw){DFEo4a_|Bi+?N6unFH@EI`T2Qy zdB4^we@#{XTRMC7>eVY(t|TNR{Gzk5v9VE6QIV06u_27`@bJIW*}%ZSpMciS&+ms) z>jN6KpiO(~)T#f-XpbH_eE9HBMhn`sgb>UMroH$-!nB}F`%9&r0#w z!<$)t>rHXdx?}+%BmXb?!&?F!QKN?h!eUz#q5Ro17Qbt?PrC2k`7Oj9arP^4$#W!sR0;aF2rnIRu;dA?4-G@4^X#Lh#zuEifQNr$$?%GP10%REVx*d&p)etJu$`5G{ zV#Rl~#1L_mSNp2{#^^QLe&aRYmKHuvKl{M3T^-bqZcQ?-62G59EtZL7TIUF#5fCm$ z!9(_q7&WoCzOsM0-zbbqj$fVmLb1;YKGgm!NjZ~|qURG!He+VO-4e8&ODMmraygk{)~vu;V~``0~0 zD~_a2<*9LWXgH{y@!7X|Z?bRr)OxTmT?-Esh9GpeINFTvYwA{ngon|#NWKzhW178o z?q219{ORKQ&yvEj!iRT|bG0Rf+qZ&`m(HOyD|PEIu_II2nb0lZ7UxytrY_d?#kcS7 za>FfYw|Ceg1!C_Klv}rslV8aA(ISzimav;@j|5v{Y^=aT0SJ9y!^gmnJNyyX`KPS(U-#^Nm3|D@GEeQ!vM82?{twerSE%0IQ*SXqJf|D@Hf>{K2#Z;>43 zh3odD5qvvZWEXi6R9rfVA7S3AC^;KxZj~;W+|jD4HycHZO&88Fzpv>q8*Se+Nj#c! zf7PUsd*|#yv8{+??UYj+u2#z}Aa>WSpN#wMV+*VtZlb+O^&}LY=k~S2+3ZaaId;%7 zgE~55HvNVi-*ZLD$Ue<1ikr=3_MqgHJPg--w`S59CJY0W?G|OZu{86Hcd-=G_JFyo z77!K9j4u(kwct)=tD>0eb)CHaxg_bw%DeqSe(Y3QyGZ@eY9&u!Yu?LMihr}(N>)Xt zCl=hP^d}u$(Q1F}RPL0-6a)J z+m6YGsph}Pp(6FR8p{eKz<1^vZ=H&bGfhLoJ&c7#F`M_(_TFIBtBXqI*=TrIWT@PT z-?I)ga9J}94L8c$v1PkO)&}8l(E}c0-yU0ADhi~n>&;upF1KdNsIc_#3bd%nhy6P@ zvx&0F8n^32kun<)N0jI z!H0Qpr&0xDyRuU$D!3cmsT5e!934pUaR#R`5S>}0!?m9)H(IHJJC%<5{Ig|MA{8p& zPNiehoK8sDw;ftCsL^MVU#dHb6r?p``l2}^L3C=tp5YXysnX9Ie2d73%bl_R+CrbzR$#34%cMv%s|8DVc$g;;BYW>&^P>OB*d{f#V>k2NZ z95THBQvAY|j|bIT_nC4xmONO{`bS1v8ojUQ2cxCLmHuF~V+(D%e`2(RGG@dIqy5@p zZe4acd4DSSQfnDyXJ28Fdl?U7MTF+05P#tES>J;`#By9u!y}KZ0Nd%HxbeZ)YZ8&B?YdKHOnD`@wd*}25RFJ0=Wpk5we+U z5ha8(ice>6JZ3@<7YmffPE?OH=chApBl@t)5z`%utP@8pUr-|GCWj31oghH^P`hF2Mk2+*7VGs+tzJ4q!nhUb#s>&GSJ~t@toveCT+C58OH+#$G3J{< zFucmbeN#6cx^wA~!O6IdAn-L{kWsgfE|Mc8!j%9j!aYzHK>8t_vdQ5sQwrh$m;x81 ziRdU7D%bdh)JT2!)jqaicV-#mP!P?VOFJHqtv*(Vsu!U7^gD^`X&={y1 zw&Ys*W2jT&%XV}b7Sx4}mk9C0w!rW$LEl7AjZyF-%wse<{wz%d!Xy4h6Hx#+0g(c& z&ZiUlQ4tXARp!N|yQByO^oTqo!iE9xPzN9a%DhlegymBZ)(fHLu0i6tL0XT3Ld_5# zsDSd6_!W+l`jp>QfVkKF!nHOpTLq5`Ign2jh{}XV#4Ls-AG$44TtyrCg6Z)TDbQSU z&eNGdl=pkWl{uIb*nwXhz@?yVXNk}02vsg}@rMOF!1`gqvQ{iu4<3OI zTCjA)X}a%o3P#ge;2|%NMmkU0q{<}WDFEz*S(t`A)R}{yLV`aIKNN)Eu_aPE!VdyO zu`j`CxgHt13T5D`@U>{ak?6u8Aee!h;t)7IWUSb!6VBLKXS_38Qi6nePFjJlM4E^z z6Zg@X(7+aWmxKGr#A$r-4QiLXtSzDpL3ET5W;i%McHrrc#33@yc`z;=1-?HZmY>0Y zQ>290wmfeC*yxjrr^uqS_*jM`_(mc%edn~dE*=?i< z8@N4-RM?L*%eZLrHF9sBbfGqcrY>AK3)z)>-cTsfO(NNQbMl$}$v*zce%F&{_G$*A z0f;jo#0d_lQ5;Hx`mvA~F)Fl%7HU*Q-#gtO9)f{l<4A;fM_0#ZU0O2Kzz@rmS zuD=%ADS4YtRUYS0A)O3?NOeedazL{ZH%uZZDxhOT578wy4?)oF@~EeLIxM(^phiRTY3}Qg zz&IO2rQ>p_KoJEO&(Q4fR~%|Wb<4S$h#=$bf_xpG91tVxmi|{NEgy z&XTjBq*<^qkC|XE0Q(pe%4;z=?X;ad_ycF$F(#7YjOwER>r2vM&dF1mmS2M~c?`_D zTFhhljNB3opMfDvpl`{OB=XTh`Iu)kbP_!?kpc@r+g>Pz<+Ct(q%0eYjNK_2%QVIB z^sJN5(_j-B2j8MMNM^4~NjunueNRWz=$U5unP0w&<+I3pCWzj8Is3YlPd+Ce%*Vf% zCwY3J6FKRp9;<##bO$m>^x5Pd6!(`sjP4E1z(v&8i)9e$#Q3r^qBC*Mfk4# zwDo#twxnNLTCr{vM7cZQk}ivTDcqcV8JXqq~{>Q)W|3n{r|P=X!# zLOdUUPG%MscS*kyzaV%Q+0Q{<gaO48Q@xhZb@x7f-2 z#v?As3u2AD6er52>4ZrR{t*RV#Z6K>CpXj&9AhIqXb4xHfFoVNR32`~fNkVLHK-9ZLYc~$m-}1KS6eQo9)*H}o$nU4!4Qt3O zt=~FZKh7_ZJf!2sJ!Uv4(kNupFr_8gTGyCqROkB2z3`#J-2&m}W3IJXjaSNx-^YkK z13Twa#Ga4cgBMEnQY9N4*_d%L(~XiR$WB=4Cc%0w0l_0eg<^+8-Ng!p?_aT%3e;&| zYC7A0GY#vk7}$Kno2`D?S=~!)QKjZ$65(CGV)5(h<*{ayCaGJ|iaGk#ylLglungT* z&5L!4R{N{x^jiystSzkAR;OEc2I}vSzHe&Nx;M7=^||{F_4nl~ZaP^BpA}91Qm5_s z`M%k#Q_%?fNT7jxeVd_8+X-o5Rq1x4iTh{9UG1*+){{B59pcr#q_ZNwsy|497+(SW}}x^?vC!ZU#LaH+r(0 znu`N^Zp<}zN%syEik0B1(Xndf2EDMfhOi~}=yI?7o=&a->4rhyD=Smwag)A6x%qQ_ z*i$WAul8XDc9P%r^>+94q&0u8e?Zi3U#@R_Y|ytkr2E{goapicSbsYkdq1Pe9`%hw zx=Fe<(^nwfG`qwyX3d*qy~6%R zA+`y>sYBz)K&o4Nv#FbI!{)ScA(_=p^i{%QPh52l=pC2tw|F9iYZ&yMd0<^MhSVBQr{Ph5Ra)UC#U}^GUL1J(>ipBGn@`_1Je~QbZ(P_zKU3?t zy7%srr|`hx*FBbV%cSPXF&gce;5cpgCVA;n%OSh&H(K`&*(vF5X*GR9>OMB!;q?#} z*OI+@UuMJoo`wg5mwFPnY+CZ_S}q*rzw0}^q5t#ENzKM1E?Z0?kl&5j?>}iQ3n~ST z;Pd(4zkmPs?c4IVW$?4Kw6wUm`1R}8g@uJLU%q_){Q1+TPxJHhA3uJao12@Ro#pX( z{O8X_1Age`d1(b8i-8 zviPu-yaDn&gzx0UcXZ@CIPfhj_-ohlArL+Q{8DF~|0o>%VzL<5SL6T(`)lL?wIa-}L=L|FqcPiY3Un4qYQHUkhlb4#TlMmtI?J-U zlPPXpH+Ga~_om|VBuqlfbJ+I$F zx{0`a=ay(0%c{c1)DYIZO1!m5%aPNAD(zdF$@11C7~h@v1V{?%&QV zzq3v4#-+OI+2x5?2)MN~$P5pW7hGBO%lOgT-u}cP@r=G`C z5gIR;CZZlM63kWeUR<`)dGmwDzP!5E&f{gG{gJ#Z<4s- zQoO3(yh^3FX}rF1X7~q<&3k<-@bjD3w;4Z;So&Pq!u|N!^k%HBGHlNTse%HTfIP0$atPS(Ri)^VOX{ZhC zL`ow`IZEQWjl}A0SSF0ouP^&q4Pegl9XVbR1N7L1$U8dS` z#)7Mu%5ru$R2$c6YLi-IlVcy%sXkZhuoTOgnd=4#>Bl4UeK(G`uixqZ5u~v_HsR{q zUw!1P7_(QXa&LM4R-1OZ^;!!RogUn47Uex;f3)b+u-k$5Pmi3BK5-nm7k%oX_o1Ak zTO7~3?>>*wuOP~<6Wfn}dE)oF=*v@!gZy4!`#tSf2cCtBy?+(A5i)akB6ia)^$qWB z$O1+-w26h6*DN>sq>N^A zel=NM(7MK2@XIZY+U7B<<)|dFU5>ns-wYL}p+-J{3OEX|J`-Su+X%%}KAD4lK%ATts=jJ3u*Y2kTE+{bY}o1VYTlA$4lcKy z*)!k`(%69M5JQ}665mN3q_GK#`c9o)qGy|x^!lwN&!r0=6;wc^6e%vGPNt+!*X1g(nt*#_UlEQG3DG#EPD*HNIbko#y6}*|==Vr$gN?k{_>iY%tdrDC=1HV_RhcDc=z|nf%2h^M4@nc%EudV4^{Ox4y70r3$1z{m}780JJMg#?B?el zwaQ5ie!}3?p6v&ha-!kN9MR1sEY!xN_kvxVa68UT!lw~O6Y!g5EBO5ag^_{J#jl}d zuB*2Gh`?djV4qyKO#LE;xiU?V zs=Ez_<>s0x>=p)aK~mpQ8lcY&S-bo^Q(XlW7^oeq7z!?oj6ltfc=lf{4kMou53~05 z1l$HEbD)nscDUNa6ky<_W44|qDfuXK6WdJcCnR}BuQ4QLYPH}(J1KjSs5|H?I}Efq z7&0+uZ)_7)w8u)ZjN;u}T~=>4M{J3687dpD(DGZ20&q6b8`!p$00Xu*mTF(mx695@ zMZ~Vs)|Uc9?#v1o1lZW^(v#8?K&vAnW~i_^TUo$8LXkvzRJoiX z?L`fepDP8~8&@LHuL)yC2H6`6_l(z!s&^)A0NLAfiYc~?hEG|9Nii7j4kV`8D%n4W z6c=e=*%0Vkg1Dg!o~l&r5`5XYMf#*JM0waIhQb0wAD|dJ9N2^}bFMNMb(gF@4F zbps(g$$^dZIDf#6RR7Xl*$T>VSs23glS;P|0HX3jh@=}=TP}Elxaq1AMAbj!;#mbG zWJ#&AB#*5V%8iFh!6Dt|T`|X}4^Xa6O2|xMbSzv1@ykkll4^g`)(!H^E%PyA_oghg zF%z!M4tMKRb^wBlq}ad>ujGz$OBH<}jBPJkWSBl?Te)n;MYhtwJSk$Ua9T`yEBjuK z4BgkI>Ghg>Ra>KV!>Dcb!(qR6iSVWi3mS-q z|29UCL!Q|u|8xq*N?m@T9uhENFWP}|qIw&avnUg#LK4be1zjG*|njCQK4gp|;mbckHgL2N-km4t9 zolZOB@_NI~u*Vl0Q6bm^B^UZM14&fWq1@*({iIN+lT3so=ecCfnkd9}BSOGlH$kF0 zTH>-z{ON^etV(~-y0;0j15XXuCtrur!Y@CrE6C82^0t1qbl&e`sEh2ug_9Gfz(>RN z&axs$>Yoc0(?iF7^4LbJgVc6QtTouC@bFSSKLEO;c^Y9|LubfvE<8IKvSp$9}Oz4JxMzx_NX= zHVu6f6Uk@bCwRoid|KFUMg%~`@#P86X@p=Fwugp%$7O^kidmPSSpcSxK`h{6iaA(5 zBf6MHvgX1q>9E5bgjLT6Hjc>J6? zsh9=6-$7e*QEvbMMuUCV1;D6f5r-_Djz{=2QP-J>DB=PszAG1#%s>nJqc<|V%8h8Q zr{J1R3WXyHvTqU)Z1aOpcUnjk?`-hVlnPhwi7 zB@j#FUgr{FHRrxFiRr8pOC^YvYjhU+HX}A?1iR7yiptkGfssqPhSt>k& zLhu8K^K@d8j$nwd19+2f)Ja_6U>jKY2Ing(o0IdI7TQ_D`(8*Ln!S|CL`uG)YNF-N z0|aj-(HpD)I3JBxiK^scT}p6V8ct~fGfPQ6y(4ib=dv$E?g9^gnn^q_kM83knLOeu z`6!Mv9-P4~=RlL#xCq+yq$u=t9$HUBj5mv%WFnqX2rp=aS9HP{4=T%sNU_;(SJ`cm763U~{XZI_}v|93lkV5?mll-s5M>H6DbHa?T!a(RQ)&_rl z0B$4?_jQMxG2rGbxCKLCKTE)ga{4!LOiLc&MnN2QMjT-vJXnZhOu=sp@pt!Y&U|GF z>ZJ*5nk?^46Sq(!r=&@brhQ7ce)1+w(Lzl@FFh5Ku9}jrDY;suHa)999SX@x@oB3#iIlO60e_Cco(st_< zQCdKj|AYbI)D{O%3CsDc>!mbTjOccUYahl^olrSA^=%4{OR%3`icVEgIKU8W}Cp zO~~m?E5iE0x)-H~F~x6diwULKGn&db7mMfg?g%u8&3g*%&!o4XzGHs*&N4>m^Wq(- zehJ*M1mP$>8&Dz%Df*O9{9&;0t#%%!AU!5PZfSJG?ZHf;X|+QEVe>(SG0ixsW80L* z$Wabu>ZxTPG>bnaWbHp&tZ7L;;F|j`A^$V~b+LA8xn6-vWoYA5Di32SPR|ycj4pSb zCVRw?C|aT}byak!yA53x-i~*Dj)`WcR4M8g?RFG8l3GYOcURJ;F#AlISaW64Tb0Pv z!jpAmoW6zov~rxo-5{v~$e7^yf*tV%ir+P>Z>5sYj8(2mt$MXslPz^O;aqM0v695P zS|i5_*Xgq2f(o#6uo5{)t*Zr%*|ECDr8>4$eY1XjD`?D~tM5py@2acs8LRJGsvnok zJGj1GVl+W5Avai)NADMqEpQT*IF z>DeW9cBJ$tsWsmzIWeW#ldh8CpYGjNU~js7@7+?)Du3zgma2J$b+&|cEmWtC;@ z-6z;h2rIooOHF_Ori_FpKbxiuh2~77=7@f4q)W5LTqAP4dChV&MY?63LCXfG7K(C_ zeoWP>8|8R|%Bk|I%43!Dvz25>nSfNSgi-5`0_0ZKcgogFLR zI$m@=rRp{Iu1wwiW0tuGQt#@F7ld1``31RT|4ms*I77t6aJHM z{eBSshjj?vg#Y~@{3qT53!Z-#4}Ud0CqhI2+VHHX_)lyLlnt}9vwt0g|KBNxalse= z6WjWw9RBVbo;~}|Z0n?(+mR#xq8yS!@gUxU1^ze6;ZMBv>oOdycfJOI78u~SK{NbM z%Hgkir^R5YMd{s2 zd|*A~@P#-U7FFo?FObVs!dw$@A7ahOX@qGM`~kTh=D*9WY`^D^9R34x3B3*VQC(|P zg#G^QA&V6G><8rPv7gX#gf0avB%bj$-ha5VYGEG{(q;_1r}I-eTvtTR+-O&jdGXpl z$?ZQNSM@h&N%I}q*l~6URxVCoLn1hTI$QS(kubXgxo$UJf$0##9Te008tT4$$Wk-l zFPUjDy1Td!S0I;Xh%4WLOxHc=J7r_a(BdzYG3@YR zretxX9a!>oJ)gB_FCFy?qb?tA-?Tm5Wd(9QHQBz#_0#M_BL(HXF`?Mfq)G5B{71=i zO6fTIyZYZC*QUp)Uyy6Ft-QmJv+!_@pO7nF=Efh8%i}QsLayxOZ0aCs_di3fH88DhR+VidS^9qH z*nQLM2pjGa>z(-Na?MSu+&!<4y%FEj26~`*u^%5$k*nu9Q8iZcHQU?wc7u@X-I?v} z@5IL*?%j9%)6m}S-#j|(&2rSN8E3wo8E_S9IJ2T0f@k4BAXodh*K0RD;RZE%>rb0L z4cx`weD)awxn_ZzF>AFj5ec4!C%UYCzwo^3)=r^I%zYW0*U@0-cdOTJdZTK;-(do&?n$#ZEa04#YnW=^aRlAW2ZJ=(oQy^NHzdDW(N#~^-j z4gd5<-OKNn=W~^Ieftz$7Q4l$We?hb&OH7bt$i{%;M~uWr^L+Lqk!O&R%T$&;+uAfTCdj__Y4Pvq==D{rGsr5i{f~pQ2V{) zIpGkU(`+kI62@7S#Mxw3N~|b{^Lz29e^(B@cAV!Q6bB(!KTLmbR9{?2t9)Bwl$nzZ z2keMw)BhM=7&pxna)VH6AdaY-k(@v8CAsE9Yf$8~R4g zln)&+Q4W#q_M0-cWXGKmHo0v|Lg+VZM?z71WhCfqBcVkS%0mD?=T6;bi%CO|vu}T@ z$Xy$$4JUEA1p9?4V^dF3q-rxh&0NC-Psce_U(KYj+GQ zD8xfW%nP7ydjk+oQ<{OLOiu#^2f#Ta@GlnVjO8M0EOVm;{us8;nhd}nW={_3u<(;Z6UL4Hlt?-P+27(@IL zk1d|=A`3`!Ww!Hxjp~_+2B;R;F?BO2yg9t~)g*pS1aOFY@26-NWfYRBZ z8N*~$26K!8Lj;H~O_69$91W!m<98T^wa^@h3@Bgf<1Aalf;^e9W)lld36>2FiVqT; z*LB$3x(0O10xO<#-f_*O#Ch?)@&U4wJhsA_(p}<_x}CDD58DnXpn|CWmB6(SJ>Eo| z{<7Oi$Aem%`m}?G=7Pz@-t97QLB>TB5g?lb+m>||W$|#RZ^20&P))!GEyFkfX#*f_ z6Dz1&2bX04i0=yFN0X`W%bzQetMD^Ht2R9BM&(-01`*FM!{m;Zh$8wiP+wc^#|7RlTuPPEB$@Ei`xdOcbGu!<5(!Fep1SQYCj-*SDZM*J zvSrBV@#Beoo5mOS1|c0d!3KpHAmpOm-Sv%i>8scE%2QKKdQ%iq;MOzGzI|qpi(6>H z=h$4-y>dehR*ZH%6@CEKuKe91Zv725anT+Eh*B;c0F2VOulWex~ms)Mov1hD=Cg$K6vU_bZ9HqVKEE zEZ%Fl@F8Rn(x;=S1+kIldYwwR@C$Mg78oS)pv4f=&8{|AT(G6i7#0^54xs$0$P;vg zGfTh>fa`LhDr|@l3xEPPf+OM(TYxW*t7qYQc(_3Zn7t#sr4j4Dgiy`FZXX!J!*%em ze5&zUKQYKz!QXgwo#=Mjc!xJnv^<%|Jie3pLVki!r@ zWB+j)n9%Zqn{r4b2%Qr$JNCmOV@G0SDX}frR@hdnIjw7i6tZygERPuFj4fnC`Se}4?1cC~m>g-f7swnQZ@aj-9SNw3vOOY~?yCk_XRhR&k+B#4O5-gUflkE?~;Gs#Op zXnt;Vwk|V!;nLG;%y%w2g$XyON5Qy|4OAFWVwa%ew!KZTH4rAG1}`lEp6n8-9p};_ zV|{37S!Z+-4ZVSG;j1DfvRPF0F`3_SZmA>|tq{xRM>3VZ5|iag>QR@qYT`EpB@h$h z-sEDSO~gfclDRs`lZy-vB7#y`+7udEiWw`pvgOScb&t!b!jUum@iS8-84kpl1M%cY zTY3=roRHoi5{Mxz8R$F?wt$1(kB%RCH_s<-N#Z3Ndx%18k*`a@WGITs!}$VE5EdjtC zMHK)dO999l32N!Lr9jA4o4#r^eT|-|`eOPzy^Klkont#PbVt=TrDR08WEd=FQ1w>p zOJ-gw&Dds5=9)WV`1pTVBn+09k=t^ij2&;yH(Acb*Bz(Kp7|Mdkzs$TvP0{63K5;gS;^AbPsi zJhWC#xZ1ptZ=V}gmK|py;<9KN6s2S#p7*RY*U!QZ0R>TWCe;o?5pUCH*I&!%&#S`-1?gp2wq#|xWHoNi zi#AfYq*urZ5WhH@o+w!~98kp7E*jBP)_^3D++p`?izXe!QuK-?`wL#B6u0X z&PBXm%*c?uGq0z{bGWmRa_7k*rR4lOLQRF&=khh-B~_(a-)qV6ZU!{9Bzbp{P(=yn zR5tRQ@<-2&*RE!HHkAk!kf8c96}6>Xnm5Ypmu>17J8n`&PAgQeD-(Cw^sTFmEM810 zAbDTTUEtf~&xRJScPw5XBlm8!eAQw(wOdwCzhe8j3X+jRKy(E%txUb3XjOE%m3}3A zqGa#6N~&ameYbdkV$x>K3P-6bSN$phn+j@Oj+IvV-suXhb7e;$68RQYzL?4t$W